15#include "auto_apms_interfaces/action/enable_hold.hpp"
23class EnableHoldTask :
public ModeExecutor<auto_apms_interfaces::action::EnableHold>
26 explicit EnableHoldTask(
const rclcpp::NodeOptions& options)
32 bool isCompleted(std::shared_ptr<const Goal> goal_ptr,
const px4_msgs::msg::VehicleStatus& vehicle_status)
final
43#include "rclcpp_components/register_node_macro.hpp"
44RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::EnableHoldTask)
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 ENABLE_HOLD_TASK_NAME[]