15#include "auto_apms_interfaces/action/rtl.hpp"
23class RTLTask :
public ModeExecutor<auto_apms_interfaces::action::RTL>
32 bool isCompleted(std::shared_ptr<const Goal> goal_ptr,
const px4_msgs::msg::VehicleStatus& vehicle_status)
35 vehicle_status.arming_state == px4_msgs::msg::VehicleStatus::ARMING_STATE_DISARMED;
41#include "rclcpp_components/register_node_macro.hpp"
42RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::RTLTask)
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)
virtual bool isCompleted(std::shared_ptr< const Goal > goal_ptr, const px4_msgs::msg::VehicleStatus &vehicle_status)
const char RTL_TASK_NAME[]