AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ModeExecutor< ActionT > Class Template Reference

Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action. More...

#include <auto_apms_px4/mode_executor.hpp>

Inheritance diagram for ModeExecutor< ActionT >:

Additional Inherited Members

- Public Member Functions inherited from ActionWrapper< ActionT >
 ActionWrapper (const std::string &action_name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr)
 Constructor.
 
 ActionWrapper (const std::string &action_name, rclcpp::Node::SharedPtr node_ptr)
 Constructor.
 
 ActionWrapper (const std::string &action_name, const rclcpp::NodeOptions &options)
 Constructor.
 

Detailed Description

template<class ActionT>
class auto_apms_px4::ModeExecutor< ActionT >

Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action.

The modes to be executed must be registered with the PX4 autopilot server before any action goals are sent. By default, only the standard PX4 modes may be executed, but the user may also implement custom modes using ModeBase. Refer to ModeExecutorFactory if you want to set up a ROS 2 node for executing your custom modes.

Usage

To register a ROS 2 node component that is able to execute for example the land mode when requested, the corresponding executor is implemented as follows:

#include "auto_apms_interfaces/action/takeoff.hpp"
#include "auto_apms_px4/mode_executor.hpp"
namespace my_namespace
{
class MyTakeoffModeExecutor : public auto_apms_px4::ModeExecutor<auto_apms_interfaces::action::Takeoff>
{
public:
explicit MyTakeoffModeExecutor(const rclcpp::NodeOptions & options)
: ModeExecutor("my_executor_name", options, FlightMode::Takeoff)
{
}
bool sendActivationCommand(const VehicleCommandClient & client,
std::shared_ptr<const Goal> goal_ptr) override final
{
return client.takeoff(goal_ptr->altitude_amsl_m, goal_ptr->heading_rad);
}
}
} // namespace my_namespace
// Register the ROS 2 node component
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(my_namespace::MyTakeoffModeExecutor)
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action...
Client for sending requests to the PX4 autopilot using the VehicleCommand topic.
Note
The package auto_apms_px4 comes with ROS 2 node components for the most common standard modes and they work out of the box.
Template Parameters
ActionTType of the ROS 2 action.

Definition at line 89 of file mode_executor.hpp.


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