15#include "auto_apms_interfaces/action/takeoff.hpp"
17#include "auto_apms_px4/mode_executor.hpp"
22class TakeoffSkill :
public ModeExecutor<auto_apms_interfaces::action::Takeoff>
25 explicit TakeoffSkill(
const rclcpp::NodeOptions & options)
26 : ModeExecutor(_AUTO_APMS_PX4__TAKEOFF_ACTION_NAME, options, FlightMode::Takeoff)
31 bool sendActivationCommand(
const VehicleCommandClient & client, std::shared_ptr<const Goal> goal_ptr)
override final
33 return client.takeoff(goal_ptr->altitude_amsl_m, goal_ptr->heading_rad);
39#include "rclcpp_components/register_node_macro.hpp"
40RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::TakeoffSkill)
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action...
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.