35 #include <rclcpp/rclcpp.hpp>
47 SDK(
int argc,
char** argv,
const std::string& node_name);
56 _skip_flight_controller_connection_check = skip;
61 rclcpp::Node::SharedPtr defaultRosHandle()
const {
return _default_ros_node; }
63 rclcpp::Time now()
const {
return _default_ros_node->now(); }
65 void addNode(rclcpp::Node::SharedPtr node) { _executor->add_node(node); }
66 void removeNode(rclcpp::Node::SharedPtr node) { _executor->remove_node(node); }
67 const rclcpp::executors::SingleThreadedExecutor::UniquePtr& executor()
const {
72 rclcpp::Node::SharedPtr _default_ros_node;
73 rclcpp::executors::SingleThreadedExecutor::UniquePtr _executor;
74 bool _skip_flight_controller_connection_check{
false};
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45
void setSkipFlightControllerConnectionCheck(bool skip)
Definition: auterion.hpp:55