35 #include <rclcpp/rclcpp.hpp>
42 class ParameterManager;
49 SDK(
int argc,
char** argv,
const std::string& node_name);
58 _skip_flight_controller_connection_check = skip;
63 rclcpp::Node::SharedPtr defaultRosHandle()
const {
return _default_ros_node; }
65 rclcpp::Time now()
const {
return _default_ros_node->now(); }
67 void addNode(rclcpp::Node::SharedPtr node) { _executor->add_node(node); }
68 void removeNode(rclcpp::Node::SharedPtr node) { _executor->remove_node(node); }
69 const rclcpp::executors::SingleThreadedExecutor::UniquePtr& executor()
const {
85 std::function<
void(
const T&)> on_change_callback =
nullptr) {
86 static_assert(std::is_same<T, bool>::value || std::is_same<T, int64_t>::value ||
87 std::is_same<T, int>::value || std::is_same<T, float>::value ||
88 std::is_same<T, double>::value || std::is_same<T, std::string>::value ||
89 std::is_same<T, std::vector<bool>>::value ||
90 std::is_same<T, std::vector<int64_t>>::value ||
91 std::is_same<T, std::vector<int>>::value ||
92 std::is_same<T, std::vector<float>>::value ||
93 std::is_same<T, std::vector<double>>::value ||
94 std::is_same<T, std::vector<std::string>>::value,
95 "Unsupported parameter data type");
99 rclcpp::Node::SharedPtr _default_ros_node;
100 rclcpp::executors::SingleThreadedExecutor::UniquePtr _executor;
101 bool _skip_flight_controller_connection_check{
false};
102 std::unique_ptr<ParameterManager> _parameter_manager;
107 std::function<
void(
const bool&)> on_change_callback);
110 std::function<
void(
const int64_t&)> on_change_callback);
112 int SDK::getParameter(
const std::string& name, std::function<
void(
const int&)> on_change_callback);
115 std::function<
void(
const float&)> on_change_callback);
118 std::function<
void(
const double&)> on_change_callback);
121 std::function<
void(
const std::string&)> on_change_callback);
124 const std::string& name, std::function<
void(
const std::vector<bool>&)> on_change_callback);
127 const std::string& name, std::function<
void(
const std::vector<int64_t>&)> on_change_callback);
130 std::function<
void(
const std::vector<int>&)> on_change_callback);
133 const std::string& name, std::function<
void(
const std::vector<float>&)> on_change_callback);
136 const std::string& name, std::function<
void(
const std::vector<double>&)> on_change_callback);
139 const std::string& name,
140 std::function<
void(
const std::vector<std::string>&)> on_change_callback);
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:47
T getParameter(const std::string &name, std::function< void(const T &)> on_change_callback=nullptr)
Get a parameter value and optionally register a callback for changes.
Definition: auterion.hpp:84
void setSkipFlightControllerConnectionCheck(bool skip)
Definition: auterion.hpp:57