15#include "auto_apms_interfaces/action/enable_hold.hpp"
17#include "auto_apms_px4/mode_executor.hpp"
22class EnableHoldSkill :
public ModeExecutor<auto_apms_interfaces::action::EnableHold>
25 explicit EnableHoldSkill(
const rclcpp::NodeOptions & options)
26 : ModeExecutor{_AUTO_APMS_PX4__ENABLE_HOLD_ACTION_NAME, options, FlightMode::Hold, false}
31 bool isCompleted(std::shared_ptr<const Goal> goal_ptr,
const px4_msgs::msg::VehicleStatus & vehicle_status)
final
42#include "rclcpp_components/register_node_macro.hpp"
43RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::EnableHoldSkill)
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.