15#include <Eigen/Geometry>
17#include "auto_apms_behavior_tree_core/node.hpp"
18#include "px4_msgs/msg/vehicle_global_position.hpp"
20#define OUTPUT_KEY_LAT "lat"
21#define OUTPUT_KEY_LON "lon"
22#define OUTPUT_KEY_ALT "alt"
23#define OUTPUT_KEY_POS "pos_vec"
25using GlobalPositionMsg = px4_msgs::msg::VehicleGlobalPosition;
30class ReadGlobalPosition :
public auto_apms_behavior_tree::core::RosSubscriberNode<GlobalPositionMsg>
32 bool first_message_received_ =
false;
33 GlobalPositionMsg last_msg_;
36 ReadGlobalPosition(
const std::string & instance_name,
const Config & config,
const Context & context)
41 static BT::PortsList providedPorts()
44 {BT::OutputPort<Eigen::Vector3d>(
45 OUTPUT_KEY_POS,
"{pos_vec}",
46 "Current global position vector (latitude [°], "
47 "longitude [°], altitude AMSL [m])"),
48 BT::OutputPort<double>(OUTPUT_KEY_LAT,
"{lat}",
"Current latitude in degree [°]"),
49 BT::OutputPort<double>(OUTPUT_KEY_LON,
"{lon}",
"Current longitude in degree [°]"),
50 BT::OutputPort<double>(OUTPUT_KEY_ALT,
"{alt}",
"Current altitude in meter (AMSL)")});
53 BT::NodeStatus onTick(
const std::shared_ptr<GlobalPositionMsg> & last_msg_ptr)
final
57 first_message_received_ =
true;
58 last_msg_ = *last_msg_ptr;
61 if (!first_message_received_)
return BT::NodeStatus::FAILURE;
63 if (
auto any_locked = getLockedPortContent(OUTPUT_KEY_POS)) {
64 setOutput(OUTPUT_KEY_LAT, last_msg_.lat);
65 setOutput(OUTPUT_KEY_LON, last_msg_.lon);
66 setOutput(OUTPUT_KEY_ALT, last_msg_.alt);
67 Eigen::Vector3d pos{last_msg_.lat, last_msg_.lon, last_msg_.alt};
68 any_locked.assign(pos);
69 return BT::NodeStatus::SUCCESS;
72 logger_,
"%s - getLockedPortContent() failed for argument %s",
73 context_.getFullyQualifiedTreeNodeName(
this).c_str(), OUTPUT_KEY_POS);
74 return BT::NodeStatus::FAILURE;
RosSubscriberNode(const std::string &instance_name, const Config &config, Context context, const rclcpp::QoS &qos={10})
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.