AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
glob_pos.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
17#include "auto_apms_behavior_tree_core/node.hpp"
18#include "px4_msgs/msg/vehicle_global_position.hpp"
19
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"
24
25using GlobalPositionMsg = px4_msgs::msg::VehicleGlobalPosition;
26
27namespace auto_apms_px4
28{
29
30class ReadGlobalPosition : public auto_apms_behavior_tree::core::RosSubscriberNode<GlobalPositionMsg>
31{
32 bool first_message_received_ = false;
33 GlobalPositionMsg last_msg_;
34
35public:
36 ReadGlobalPosition(const std::string & instance_name, const Config & config, const Context & context)
37 : RosSubscriberNode{instance_name, config, context, rclcpp::SensorDataQoS{}}
38 {
39 }
40
41 static BT::PortsList providedPorts()
42 {
43 return providedBasicPorts(
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)")});
51 }
52
53 BT::NodeStatus onTick(const std::shared_ptr<GlobalPositionMsg> & last_msg_ptr) final
54 {
55 // Check if a new message was received
56 if (last_msg_ptr) {
57 first_message_received_ = true;
58 last_msg_ = *last_msg_ptr;
59 }
60
61 if (!first_message_received_) return BT::NodeStatus::FAILURE;
62
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;
70 }
71 RCLCPP_ERROR(
72 logger_, "%s - getLockedPortContent() failed for argument %s",
73 context_.getFullyQualifiedTreeNodeName(this).c_str(), OUTPUT_KEY_POS);
74 return BT::NodeStatus::FAILURE;
75 }
76};
77
78} // namespace auto_apms_px4
79
80AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_px4::ReadGlobalPosition)
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:40
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.
Definition mode.hpp:26