21#ifndef EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
22#define EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
27#include "tf2_ros/buffer.hpp"
40 explicit RTTFBuffer(
const rclcpp::Clock::SharedPtr & clock)
41 : tf2_ros::Buffer(clock)
45 : Buffer(
std::make_shared<rclcpp::Clock>(RCL_ROS_TIME))
47 RCLCPP_WARN(rclcpp::get_logger(
"RTTFBuffer"),
48 "You should be creating this RTTFBuffer with your clock."
49 "Using default clock RCL_ROS_TIME");
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;
#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