AutoAPMS
Resilient Robot Mission Management
All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Modules Pages
get_position.cpp
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#include <Eigen/Geometry>
16#include <type_traits>
17
18#include "auto_apms_behavior_tree_core/node.hpp"
19#include "px4_msgs/msg/vehicle_global_position.hpp"
20#include "px4_msgs/msg/vehicle_local_position.hpp"
21
22#define OUTPUT_KEY_LAT "lat"
23#define OUTPUT_KEY_LON "lon"
24#define OUTPUT_KEY_ALT "alt"
25#define OUTPUT_KEY_N "north"
26#define OUTPUT_KEY_E "east"
27#define OUTPUT_KEY_D "down"
28#define OUTPUT_KEY_VEC "vector"
29
30using GlobalPositionMsg = px4_msgs::msg::VehicleGlobalPosition;
31using LocalPositionMsg = px4_msgs::msg::VehicleLocalPosition;
32
33namespace auto_apms_px4
34{
35
36template <class T>
37class GetPosition : public auto_apms_behavior_tree::core::RosSubscriberNode<T>
38{
39 bool first_message_received_ = false;
40 T last_msg_;
41
42public:
43 GetPosition(
44 const std::string & instance_name, const BT::NodeConfig & config,
45 const auto_apms_behavior_tree::core::RosNodeContext & context)
46 : auto_apms_behavior_tree::core::RosSubscriberNode<T>{instance_name, config, context, rclcpp::SensorDataQoS{}}
47 {
48 }
49
50 static BT::PortsList providedPorts()
51 {
52 if constexpr (std::is_same_v<T, GlobalPositionMsg>) {
53 return {
54 BT::OutputPort<Eigen::MatrixXd>(
55 OUTPUT_KEY_VEC, "{pos_vec}",
56 "Current global position vector (latitude [°], longitude [°], altitude AMSL [m])"),
57 BT::OutputPort<double>(OUTPUT_KEY_LAT, "{lat}", "Current latitude in degree [°]"),
58 BT::OutputPort<double>(OUTPUT_KEY_LON, "{lon}", "Current longitude in degree [°]"),
59 BT::OutputPort<double>(OUTPUT_KEY_ALT, "{alt}", "Current altitude in meter (AMSL)")};
60 } else {
61 return {
62 BT::OutputPort<Eigen::MatrixXd>(
63 OUTPUT_KEY_VEC, "{pos_vec}", "Current local position vector (north [m], east [m], down [m])"),
64 BT::OutputPort<double>(OUTPUT_KEY_N, "{north}", "Current north [m] relative to origin"),
65 BT::OutputPort<double>(OUTPUT_KEY_E, "{east}", "Current east [m] relative to origin"),
66 BT::OutputPort<double>(OUTPUT_KEY_D, "{down}", "Current down [m] relative to origin")};
67 }
68 }
69
70 BT::NodeStatus onTick(const std::shared_ptr<T> & last_msg_ptr) final
71 {
72 // Check if a new message was received
73 if (last_msg_ptr) {
74 first_message_received_ = true;
75 last_msg_ = *last_msg_ptr;
76 }
77
78 if (!first_message_received_) return BT::NodeStatus::FAILURE;
79
80 if constexpr (std::is_same_v<T, GlobalPositionMsg>) {
81 Eigen::MatrixXd mat(1, 3);
82 mat(0, 0) = last_msg_.lat;
83 mat(0, 1) = last_msg_.lon;
84 mat(0, 2) = last_msg_.alt;
85 this->setOutput(OUTPUT_KEY_LAT, mat(0, 0));
86 this->setOutput(OUTPUT_KEY_LON, mat(0, 1));
87 this->setOutput(OUTPUT_KEY_ALT, mat(0, 2));
88 this->setOutput(OUTPUT_KEY_VEC, mat);
89 } else {
90 Eigen::MatrixXd mat(1, 3);
91 mat(0, 0) = last_msg_.x;
92 mat(0, 1) = last_msg_.y;
93 mat(0, 2) = last_msg_.z;
94 this->setOutput(OUTPUT_KEY_N, mat(0, 0));
95 this->setOutput(OUTPUT_KEY_E, mat(0, 1));
96 this->setOutput(OUTPUT_KEY_D, mat(0, 2));
97 this->setOutput(OUTPUT_KEY_VEC, mat);
98 }
99
100 return BT::NodeStatus::SUCCESS;
101 }
102};
103
104} // namespace auto_apms_px4
105
106AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_px4::GetPosition<GlobalPositionMsg>)
107AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_px4::GetPosition<LocalPositionMsg>)
RosSubscriberNode(const std::string &instance_name, const Config &config, Context context, const rclcpp::QoS &qos={10})
#define AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(type)
Macro for registering a behavior tree node plugin.
Definition node.hpp:43
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.
Definition mode.hpp:26