21#ifndef EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
22#define EASYNAV_COMMON_TYPES__RTTFBUFFER_HPP_
26#include "tf2_ros/buffer.h"
27#include "rclcpp/rclcpp.hpp"
39 explicit RTTFBuffer(
const rclcpp::Clock::SharedPtr & clock)
40 : tf2_ros::Buffer(clock)
44 : Buffer(
std::make_shared<rclcpp::Clock>(RCL_ROS_TIME))
46 RCLCPP_WARN(rclcpp::get_logger(
"RTTFBuffer"),
47 "You should be creating this RTTFBuffer with your clock."
48 "Using default clock RCL_ROS_TIME");
#define SINGLETON_DEFINITIONS(ClassName)
Definition Singleton.hpp:75
Provides functionality for RTTFBuffer.
Definition RTTFBuffer.hpp:37
RTTFBuffer()
Definition RTTFBuffer.hpp:43
RTTFBuffer(const rclcpp::Clock::SharedPtr &clock)
Definition RTTFBuffer.hpp:39
Definition RTTFBuffer.hpp:30
Definition PointPerception.hpp:56