16#ifndef EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
17#define EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
22#include "tf2_ros/buffer.hpp"
35 explicit RTTFBuffer(
const rclcpp::Clock::SharedPtr & clock)
36 : tf2_ros::Buffer(clock)
40 : Buffer(
std::make_shared<rclcpp::Clock>(RCL_ROS_TIME))
42 RCLCPP_WARN(rclcpp::get_logger(
"RTTFBuffer"),
43 "You should be creating this RTTFBuffer with your clock."
44 "Using default clock RCL_ROS_TIME");
57 if (tf_info_.tf_prefix !=
"") {
58 tf_info_.map_frame = tf_info_.tf_prefix +
"/" + tf_info_.map_frame;
59 tf_info_.odom_frame = tf_info_.tf_prefix +
"/" + tf_info_.odom_frame;
60 tf_info_.robot_frame = tf_info_.tf_prefix +
"/" + tf_info_.robot_frame;
61 tf_info_.robot_footprint_frame = tf_info_.tf_prefix +
"/" + tf_info_.robot_footprint_frame;
62 tf_info_.world_frame = tf_info_.tf_prefix +
"/" + tf_info_.world_frame;
#define SINGLETON_DEFINITIONS(ClassName)
Definition Singleton.hpp:70
Provides functionality for RTTFBuffer.
Definition RTTFBuffer.hpp:33
const TFInfo & get_tf_info() const
Definition RTTFBuffer.hpp:47
RTTFBuffer()
Definition RTTFBuffer.hpp:39
void set_tf_info(const TFInfo &tf_info)
Definition RTTFBuffer.hpp:52
RTTFBuffer(const rclcpp::Clock::SharedPtr &clock)
Definition RTTFBuffer.hpp:35
Definition CircularBuffer.hpp:23
Definition PointPerception.hpp:49
Aggregated TF configuration used across EasyNav.
Definition TFInfo.hpp:25