15#include <Eigen/Geometry>
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"
35 ReadGlobalPosition(
const std::string& instance_name,
const Config& config,
const Context& context)
40 static BT::PortsList providedPorts()
43 "Current global position vector (latitude [°], "
44 "longitude [°], altitude AMSL [m])"),
45 BT::OutputPort<double>(
OUTPUT_KEY_LAT,
"{lat}",
"Current latitude in degree [°]"),
46 BT::OutputPort<double>(
OUTPUT_KEY_LON,
"{lon}",
"Current longitude in degree [°]"),
47 BT::OutputPort<double>(
OUTPUT_KEY_ALT,
"{alt}",
"Current altitude in meter (AMSL)") });
50 BT::NodeStatus onTick(
const std::shared_ptr<GlobalPositionMsg>& last_msg_ptr)
final
55 last_msg_ = *last_msg_ptr;
63 Eigen::Vector3d pos{ last_msg_.lat, last_msg_.lon, last_msg_.alt };
64 any_locked.assign(pos);
65 return BT::NodeStatus::SUCCESS;
67 RCLCPP_ERROR(
logger_,
"%s - getLockedPortContent() failed for argument %s", name().c_str(),
OUTPUT_KEY_POS);
68 return BT::NodeStatus::FAILURE;
Abstract class to wrap a Topic subscriber. Considering the example in the tutorial: https://docs....
static BT::PortsList providedBasicPorts(BT::PortsList addition)
RosSubscriberNode(const std::string &instance_name, const Config &config, const Context &context, const rclcpp::QoS &qos={ 10 })
const rclcpp::Logger logger_
px4_msgs::msg::VehicleGlobalPosition GlobalPositionMsg
#define AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(type)
Macro for registering a behavior tree node plugin.