Easy Navigation
Loading...
Searching...
No Matches
RTTFBuffer.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// This file is part of the project Easy Navigation (EasyNav in short)
4// licensed under the GNU General Public License v3.0.
5// See <http://www.gnu.org/licenses/> for details.
6//
7// Easy Navigation program is free software: you can redistribute it and/or modify
8// it under the terms of the GNU General Public License as published by
9// the Free Software Foundation, either version 3 of the License, or
10// (at your option) any later version.
11//
12// This program is distributed in the hope that it will be useful,
13// but WITHOUT ANY WARRANTY; without even the implied warranty of
14// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15// GNU General Public License for more details.
16//
17// You should have received a copy of the GNU General Public License
18// along with this program. If not, see <http://www.gnu.org/licenses/>.
19
20
21#ifndef EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
22#define EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
23
26
27#include "tf2_ros/buffer.hpp"
28
29namespace easynav
30{
31
37class RTTFBuffer : public tf2_ros::Buffer, public Singleton<RTTFBuffer>
38{
39public:
40 explicit RTTFBuffer(const rclcpp::Clock::SharedPtr & clock)
41 : tf2_ros::Buffer(clock)
42 {}
43
44 explicit RTTFBuffer()
45 : Buffer(std::make_shared<rclcpp::Clock>(RCL_ROS_TIME))
46 {
47 RCLCPP_WARN(rclcpp::get_logger("RTTFBuffer"),
48 "You should be creating this RTTFBuffer with your clock."
49 "Using default clock RCL_ROS_TIME");
50 }
51
52 const TFInfo & get_tf_info() const
53 {
54 return tf_info_;
55 }
56
57 void set_tf_info(const TFInfo & tf_info)
58 {
59 tf_info_ = tf_info;
60
61 // Apply tf_prefix to all frames
62 if (tf_info_.tf_prefix != "") {
63 tf_info_.map_frame = tf_info_.tf_prefix + "/" + tf_info_.map_frame;
64 tf_info_.odom_frame = tf_info_.tf_prefix + "/" + tf_info_.odom_frame;
65 tf_info_.robot_frame = tf_info_.tf_prefix + "/" + tf_info_.robot_frame;
66 tf_info_.robot_footprint_frame = tf_info_.tf_prefix + "/" + tf_info_.robot_footprint_frame;
67 tf_info_.world_frame = tf_info_.tf_prefix + "/" + tf_info_.world_frame;
68 }
69 }
70
71private:
72 TFInfo tf_info_;
73
75};
76
77} // namespace easynav
78
79
80#endif // EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
#define SINGLETON_DEFINITIONS(ClassName)
Definition Singleton.hpp:75
Provides functionality for RTTFBuffer.
Definition RTTFBuffer.hpp:38
const TFInfo & get_tf_info() const
Definition RTTFBuffer.hpp:52
RTTFBuffer()
Definition RTTFBuffer.hpp:44
void set_tf_info(const TFInfo &tf_info)
Definition RTTFBuffer.hpp:57
RTTFBuffer(const rclcpp::Clock::SharedPtr &clock)
Definition RTTFBuffer.hpp:40
Definition CircularBuffer.hpp:28
Definition PointPerception.hpp:54
Aggregated TF configuration used across EasyNav.
Definition TFInfo.hpp:30