15#include "auto_apms_interfaces/action/mission.hpp"
23class MissionTask :
public ModeExecutor<auto_apms_interfaces::action::Mission>
26 explicit MissionTask(
const rclcpp::NodeOptions& options)
32 bool sendActivationCommand(
const VehicleCommandClient& client, std::shared_ptr<const Goal> goal_ptr)
final
34 if (goal_ptr->do_restart)
36 return client.StartMission();
38 return client.SyncActivateFlightMode(FlightMode::Mission);
44#include "rclcpp_components/register_node_macro.hpp"
45RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::MissionTask)
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 MISSION_TASK_NAME[]