15#include "auto_apms_behavior_tree_core/node.hpp"
16#include "auto_apms_interfaces/action/arm_disarm.hpp"
18#define INPUT_KEY_WAIT "wait_until_ready_to_arm"
23class ArmAction :
public auto_apms_behavior_tree::core::RosActionNode<auto_apms_interfaces::action::ArmDisarm>
26 using RosActionNode::RosActionNode;
28 static BT::PortsList providedPorts()
32 "Wait for the UAV to be ready for arming. If false and UAV is not "
37 bool setGoal(Goal & goal)
39 goal.arming_state = Goal::ARMING_STATE_ARM;
40 if (
const BT::Expected<bool> expected = getInput<bool>(INPUT_KEY_WAIT)) {
41 goal.wait_until_ready_to_arm = expected.value();
43 RCLCPP_ERROR(logger_,
"%s", expected.error().c_str());
static BT::PortsList providedBasicPorts(BT::PortsList addition)
#define AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(type)
Macro for registering a behavior tree node plugin.
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.