15#include "auto_apms_behavior_tree_core/node.hpp"
16#include "auto_apms_interfaces/action/go_to.hpp"
18#define INPUT_KEY_LATITUDE "lat"
19#define INPUT_KEY_LONGITUDE "lon"
20#define INPUT_KEY_ALTITUDE "alt"
25class GoToAction :
public auto_apms_behavior_tree::core::RosActionNode<auto_apms_interfaces::action::GoTo>
28 using RosActionNode::RosActionNode;
30 static BT::PortsList providedPorts()
33 {BT::InputPort<double>(INPUT_KEY_LATITUDE,
"Target latitude"),
34 BT::InputPort<double>(INPUT_KEY_LONGITUDE,
"Target longitude"),
35 BT::InputPort<double>(INPUT_KEY_ALTITUDE,
"Target altitude in meter (AMSL)")});
38 bool setGoal(Goal & goal)
40 if (
const BT::Expected<double> expected = getInput<double>(INPUT_KEY_LATITUDE)) {
41 goal.lat = expected.value();
43 RCLCPP_ERROR(logger_,
"%s", expected.error().c_str());
46 if (
const BT::Expected<double> expected = getInput<double>(INPUT_KEY_LONGITUDE)) {
47 goal.lon = expected.value();
49 RCLCPP_ERROR(logger_,
"%s", expected.error().c_str());
52 if (
const BT::Expected<double> expected = getInput<double>(INPUT_KEY_ALTITUDE)) {
53 goal.alt = expected.value();
55 RCLCPP_ERROR(logger_,
"%s", expected.error().c_str());
58 goal.head_towards_destination =
true;
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.