15#include <Eigen/Geometry>
18#include "auto_apms_interfaces/action/go_to.hpp"
20#define INPUT_KEY_VEC "vector"
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)
40 if (any_locked->empty())
42 RCLCPP_ERROR(
logger_,
"%s - Value at blackboard entry {%s} is empty", name().c_str(),
INPUT_KEY_VEC);
45 else if (Eigen::Vector3d* vec_ptr = any_locked->castPtr<Eigen::Vector3d>())
47 goal.lat = vec_ptr->x();
48 goal.lon = vec_ptr->y();
49 goal.alt = vec_ptr->z();
50 goal.head_towards_destination =
true;
59 RCLCPP_ERROR(
logger_,
"%s - getLockedPortContent() failed for argument %s", name().c_str(),
INPUT_KEY_VEC);
Abstract class to wrap rclcpp_action::Client<>
typename auto_apms_interfaces::action::GoTo::Goal Goal
static BT::PortsList providedBasicPorts(BT::PortsList addition)
const rclcpp::Logger logger_
#define AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(type)
Macro for registering a behavior tree node plugin.