35 #include <auterion_sdk/exception/exception.hpp>
36 #include <rclcpp/rclcpp.hpp>
43 class ParameterManager;
59 skip_flight_controller_connection_check = skip;
77 skip_message_compatibility_check = skip;
81 void validate()
const {
82 if (skip_flight_controller_connection_check && !skip_message_compatibility_check) {
84 "Cannot check message compatibility if connection check is skipped. "
85 "Enable flight controller connection check, or disable message compatibility "
90 bool skip_flight_controller_connection_check{
false};
91 bool skip_message_compatibility_check{
true};
99 SDK(
int argc,
char** argv,
const std::string& node_name);
103 [[deprecated(
"Use run(RunOptions) instead, this method will be removed in a future release.")]]
111 _skip_flight_controller_connection_check = skip;
116 rclcpp::Node::SharedPtr defaultRosHandle()
const {
return _default_ros_node; }
118 rclcpp::Time now()
const {
return _default_ros_node->now(); }
120 void addNode(rclcpp::Node::SharedPtr node) { _executor->add_node(node); }
121 void removeNode(rclcpp::Node::SharedPtr node) { _executor->remove_node(node); }
123 const rclcpp::executors::SingleThreadedExecutor::UniquePtr& executor()
const {
128 template <
typename T>
129 static constexpr
void verify_param() {
130 static_assert(std::is_same<T, bool>::value || std::is_same<T, int64_t>::value ||
131 std::is_same<T, int>::value || std::is_same<T, float>::value ||
132 std::is_same<T, double>::value || std::is_same<T, std::string>::value ||
133 std::is_same<T, std::vector<bool>>::value ||
134 std::is_same<T, std::vector<int64_t>>::value ||
135 std::is_same<T, std::vector<int>>::value ||
136 std::is_same<T, std::vector<float>>::value ||
137 std::is_same<T, std::vector<double>>::value ||
138 std::is_same<T, std::vector<std::string>>::value,
139 "Unsupported parameter data type");
153 template <
typename T>
155 std::function<
void(
const T&)> on_change_callback =
nullptr) {
169 template <
typename T>
175 rclcpp::Node::SharedPtr _default_ros_node;
176 rclcpp::executors::SingleThreadedExecutor::UniquePtr _executor;
177 bool _skip_flight_controller_connection_check{
false};
178 std::unique_ptr<ParameterManager> _parameter_manager;
183 std::function<
void(
const bool&)> on_change_callback);
187 std::function<
void(
const int64_t&)> on_change_callback);
190 int SDK::getParameter(
const std::string& name, std::function<
void(
const int&)> on_change_callback);
194 std::function<
void(
const float&)> on_change_callback);
198 std::function<
void(
const double&)> on_change_callback);
202 std::function<
void(
const std::string&)> on_change_callback);
206 const std::string& name, std::function<
void(
const std::vector<bool>&)> on_change_callback);
210 const std::string& name, std::function<
void(
const std::vector<int64_t>&)> on_change_callback);
214 std::function<
void(
const std::vector<int>&)> on_change_callback);
218 const std::string& name, std::function<
void(
const std::vector<float>&)> on_change_callback);
222 const std::string& name, std::function<
void(
const std::vector<double>&)> on_change_callback);
226 const std::string& name,
227 std::function<
void(
const std::vector<std::string>&)> on_change_callback);
251 void SDK::setParameter(
const std::string& name,
const std::vector<int64_t>& value);
257 void SDK::setParameter(
const std::string& name,
const std::vector<float>& value);
260 void SDK::setParameter(
const std::string& name,
const std::vector<double>& value);
263 void SDK::setParameter(
const std::string& name,
const std::vector<std::string>& value);
Exception thrown for invalid arguments.
Definition: exception.hpp:82
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:97
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:154
void setParameter(const std::string &name, const T &value)
Set a parameter.
Definition: auterion.hpp:170
void setSkipFlightControllerConnectionCheck(bool skip)
Definition: auterion.hpp:110
Options for SDK run() method.
Definition: auterion.hpp:50
RunOptions & withSkipMessageCompatibilityCheck(bool skip)
Skip the check for message compatibility.
Definition: auterion.hpp:76
RunOptions & withSkipFlightControllerConnectionCheck(bool skip)
Skip the check for flight controller connection.
Definition: auterion.hpp:58