AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
glob_pos.cpp
Go to the documentation of this file.
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
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::RosSubscriberNode<GlobalPositionMsg>
31{
32 GlobalPositionMsg last_msg_;
33
34public:
35 ReadGlobalPosition(const std::string& instance_name, const Config& config, const Context& context)
36 : RosSubscriberNode{ instance_name, config, context, rclcpp::SensorDataQoS{} }
37 {
38 }
39
40 static BT::PortsList providedPorts()
41 {
42 return providedBasicPorts({ BT::OutputPort<Eigen::Vector3d>(OUTPUT_KEY_POS, "{pos_vec}",
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)") });
48 }
49
50 BT::NodeStatus onTick(const std::shared_ptr<GlobalPositionMsg>& last_msg_ptr) final
51 {
52 // Check if a new message was received
53 if (last_msg_ptr)
54 {
55 last_msg_ = *last_msg_ptr;
56 }
57
58 if (auto any_locked = getLockedPortContent(OUTPUT_KEY_POS))
59 {
60 setOutput(OUTPUT_KEY_LAT, last_msg_.lat);
61 setOutput(OUTPUT_KEY_LON, last_msg_.lon);
62 setOutput(OUTPUT_KEY_ALT, last_msg_.alt);
63 Eigen::Vector3d pos{ last_msg_.lat, last_msg_.lon, last_msg_.alt };
64 any_locked.assign(pos);
65 return BT::NodeStatus::SUCCESS;
66 }
67 RCLCPP_ERROR(logger_, "%s - getLockedPortContent() failed for argument %s", name().c_str(), OUTPUT_KEY_POS);
68 return BT::NodeStatus::FAILURE;
69 }
70};
71
72} // namespace auto_apms_px4
73
74AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_px4::ReadGlobalPosition)
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 })
#define OUTPUT_KEY_LAT
Definition glob_pos.cpp:20
#define OUTPUT_KEY_ALT
Definition glob_pos.cpp:22
#define OUTPUT_KEY_LON
Definition glob_pos.cpp:21
px4_msgs::msg::VehicleGlobalPosition GlobalPositionMsg
Definition glob_pos.cpp:25
#define OUTPUT_KEY_POS
Definition glob_pos.cpp:23
#define AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(type)
Macro for registering a behavior tree node plugin.
Definition node.hpp:30