15#include "auto_apms_interfaces/action/takeoff.hpp"
17#include "auto_apms_behavior_tree_core/node.hpp"
19#define INPUT_KEY_ALTITUDE "alt"
24class TakeoffAction :
public auto_apms_behavior_tree::core::RosActionNode<auto_apms_interfaces::action::Takeoff>
27 using RosActionNode::RosActionNode;
29 static BT::PortsList providedPorts()
31 return providedBasicPorts({BT::InputPort<double>(INPUT_KEY_ALTITUDE,
"Target takeoff altitude in meter (AMSL)")});
34 bool setGoal(Goal & goal)
36 if (
const BT::Expected<double> expected = getInput<double>(INPUT_KEY_ALTITUDE)) {
37 goal.altitude_amsl_m = expected.value();
39 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.