PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::NodeWithModeExecutor< ModeExecutorT, ModeT > Class Template Reference

A ROS2 node which instantiates a mode executor and its owned mode, and handles their registration with PX4. More...

#include <px4_ros2/components/node_with_mode.hpp>

Inheritance diagram for px4_ros2::NodeWithModeExecutor< ModeExecutorT, ModeT >:

Public Member Functions

 NodeWithModeExecutor (std::string node_name, bool enable_debug_output=false)
 
ModeT & getMode () const
 

Detailed Description

template<typename ModeExecutorT, typename ModeT>
class px4_ros2::NodeWithModeExecutor< ModeExecutorT, ModeT >

A ROS2 node which instantiates a mode executor and its owned mode, and handles their registration with PX4.

Assumes mode executor constructor signature is ModeExecutorT(rclcpp::Node, ModeT).

Template Parameters
ModeExecutorTThe mode executor type, which must be derived from px4_ros2::ModeExecutorBase.
ModeTThe mode type owned by the executor, which must be derived from px4_ros2::ModeBase.

Example usage:

class MyMode : public px4_ros2::ModeBase {...};
class MyExecutor : public px4_ros2::ModeExecutor {...};
rclcpp::spin(std::make_shared<px4_ros2::NodeWithMode<MyExecutor, MyMode>>("my_node"));
Base class for a mode.
Definition: mode.hpp:70
A ROS2 node which instantiates a control mode and handles its registration with PX4.
Definition: node_with_mode.hpp:33

The documentation for this class was generated from the following file: