SDK execution class. All callbacks are called on the same thread.
More...
#include <auterion_sdk/auterion.hpp>
|
| SDK (int argc, char **argv, const std::string &node_name) |
|
void | setSkipFlightControllerConnectionCheck (bool skip) |
|
void | run () |
|
rclcpp::Node::SharedPtr | defaultRosHandle () const |
|
rclcpp::Time | now () const |
|
void | addNode (rclcpp::Node::SharedPtr node) |
|
void | removeNode (rclcpp::Node::SharedPtr node) |
|
const rclcpp::executors::SingleThreadedExecutor::UniquePtr & | executor () const |
|
template<typename T > |
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. More...
|
|
|
template<> |
bool | getParameter (const std::string &name, std::function< void(const bool &)> on_change_callback) |
|
template<> |
int64_t | getParameter (const std::string &name, std::function< void(const int64_t &)> on_change_callback) |
|
template<> |
int | getParameter (const std::string &name, std::function< void(const int &)> on_change_callback) |
|
template<> |
float | getParameter (const std::string &name, std::function< void(const float &)> on_change_callback) |
|
template<> |
double | getParameter (const std::string &name, std::function< void(const double &)> on_change_callback) |
|
template<> |
std::string | getParameter (const std::string &name, std::function< void(const std::string &)> on_change_callback) |
|
template<> |
std::vector< bool > | getParameter (const std::string &name, std::function< void(const std::vector< bool > &)> on_change_callback) |
|
template<> |
std::vector< int64_t > | getParameter (const std::string &name, std::function< void(const std::vector< int64_t > &)> on_change_callback) |
|
template<> |
std::vector< int > | getParameter (const std::string &name, std::function< void(const std::vector< int > &)> on_change_callback) |
|
template<> |
std::vector< float > | getParameter (const std::string &name, std::function< void(const std::vector< float > &)> on_change_callback) |
|
template<> |
std::vector< double > | getParameter (const std::string &name, std::function< void(const std::vector< double > &)> on_change_callback) |
|
template<> |
std::vector< std::string > | getParameter (const std::string &name, std::function< void(const std::vector< std::string > &)> on_change_callback) |
|
SDK execution class. All callbacks are called on the same thread.
◆ getParameter()
template<typename T >
T auterion::SDK::getParameter |
( |
const std::string & |
name, |
|
|
std::function< void(const T &)> |
on_change_callback = nullptr |
|
) |
| |
|
inline |
Get a parameter value and optionally register a callback for changes.
The parameter name must be defined in auterion-app.yml. The type must match (or be convertible from) the parameter type in the yaml definition.
- Parameters
-
name | parameter name |
on_change_callback | optional callback for dynamic parameter changes |
- Exceptions
-
◆ setSkipFlightControllerConnectionCheck()
void auterion::SDK::setSkipFlightControllerConnectionCheck |
( |
bool |
skip | ) |
|
|
inline |
By default, run() will first check if the flight controller is connected and ensure message format compatibility. This method can be used to disable that check.
- Parameters
-
The documentation for this class was generated from the following file: