|
|
| SDK (int argc, char **argv, const std::string &node_name) |
| |
| void | setSkipFlightControllerConnectionCheck (bool skip) |
| |
|
void | run (RunOptions options=RunOptions()) |
| |
|
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<typename T > |
| void | setParameter (const std::string &name, const T &value) |
| | Set a parameter. 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) |
| |
|
template<> |
| void | setParameter (const std::string &name, const bool &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const int64_t &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const int &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const float &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const double &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::string &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::vector< bool > &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::vector< int64_t > &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::vector< int > &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::vector< float > &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::vector< double > &value) |
| |
|
template<> |
| void | setParameter (const std::string &name, const std::vector< std::string > &value) |
| |
SDK execution class. All callbacks are called on the same thread.