15#include <Eigen/Geometry>
17#include "auto_apms_behavior_tree_core/node.hpp"
18#include "auto_apms_interfaces/action/go_to.hpp"
20#define INPUT_KEY_VEC "vector"
25class GoToVectorAction :
public auto_apms_behavior_tree::core::RosActionNode<auto_apms_interfaces::action::GoTo>
28 using RosActionNode::RosActionNode;
30 static BT::PortsList providedPorts()
33 {BT::InputPort<Eigen::Vector3d>(INPUT_KEY_VEC,
"Target position as a pointer to a vector")});
36 bool setGoal(Goal & goal)
38 if (
auto any_locked = getLockedPortContent(INPUT_KEY_VEC)) {
39 if (any_locked->empty()) {
41 logger_,
"%s - Value at blackboard entry {%s} is empty", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
44 }
else if (Eigen::Vector3d * vec_ptr = any_locked->castPtr<Eigen::Vector3d>()) {
45 goal.lat = vec_ptr->x();
46 goal.lon = vec_ptr->y();
47 goal.alt = vec_ptr->z();
48 goal.head_towards_destination =
true;
52 logger_,
"%s - Failed to cast pointer {%s}", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
58 logger_,
"%s - getLockedPortContent() failed for argument %s",
59 context_.getFullyQualifiedTreeNodeName(
this).c_str(), INPUT_KEY_VEC);
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.