16#include "auto_apms_interfaces/action/arm_disarm.hpp"
18#define INPUT_KEY_WAIT "wait_until_ready_to_arm"
26 using RosActionNode::RosActionNode;
28 static BT::PortsList providedPorts()
31 "Wait for the UAV to be ready for arming. If false and UAV is not "
36 bool setGoal(
Goal& goal)
38 goal.arming_state = Goal::ARMING_STATE_ARM;
39 goal.wait_until_ready_to_arm = getInput<bool>(
INPUT_KEY_WAIT).value();
Abstract class to wrap rclcpp_action::Client<>
typename auto_apms_interfaces::action::ArmDisarm::Goal Goal
static BT::PortsList providedBasicPorts(BT::PortsList addition)
#define AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(type)
Macro for registering a behavior tree node plugin.