15#include "auto_apms_interfaces/action/land.hpp"
23class LandTask :
public ModeExecutor<auto_apms_interfaces::action::Land>
31 bool sendActivationCommand(
const VehicleCommandClient& client, std::shared_ptr<const Goal> goal_ptr)
40#include "rclcpp_components/register_node_macro.hpp"
41RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::LandTask)
VehicleCommandClient::FlightMode FlightMode
ModeExecutor(const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr, uint8_t mode_id, bool deactivate_before_completion=true, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
const char LAND_TASK_NAME[]