Go to the documentation of this file.
33 #ifndef TF2_TIME_CACHE_H
34 #define TF2_TIME_CACHE_H
42 #include <ros/message_forward.h>
57 class TimeCacheInterface
61 virtual bool getData(
ros::Time time, TransformStorage & data_out, std::string* error_str = 0)=0;
64 virtual bool insertData(
const TransformStorage& new_data)=0;
95 class TimeCache :
public TimeCacheInterface
107 virtual bool getData(
ros::Time time, TransformStorage & data_out, std::string* error_str = 0);
108 virtual bool insertData(
const TransformStorage& new_data);
128 inline uint8_t
findClosest(TransformStorage*& one, TransformStorage*& two,
ros::Time target_time, std::string* error_str);
130 inline void interpolate(
const TransformStorage& one,
const TransformStorage& two,
ros::Time time, TransformStorage& output);
139 class StaticCache :
public TimeCacheInterface
144 virtual bool getData(
ros::Time time, TransformStorage & data_out, std::string* error_str = 0);
145 virtual bool insertData(
const TransformStorage& new_data);
163 #endif // TF2_TIME_CACHE_H
std::pair< ros::Time, CompactFrameID > P_TimeAndFrameID
ros::Duration max_storage_time_
static const int MIN_INTERPOLATION_DISTANCE
Number of nano-seconds to not interpolate below.
virtual ros::Time getOldestTimestamp()
TransformStorage storage_
virtual bool insertData(const TransformStorage &new_data, std::string *error_str=0)
virtual unsigned int getListLength()=0
virtual unsigned int getListLength()
boost::shared_ptr< TimeCacheInterface > TimeCacheInterfacePtr
::geometry_msgs::TransformStamped_< std::allocator< void > > TransformStamped
std::deque< TransformStorage > L_TransformStorage
virtual bool insertData(const TransformStorage &new_data, std::string *error_str=0)
virtual CompactFrameID getParent(ros::Time time, std::string *error_str)=0
virtual bool getData(ros::Time time, TransformStorage &data_out, std::string *error_str=0)
virtual CompactFrameID getParent(ros::Time time, std::string *error_str)
static const unsigned int MAX_LENGTH_LINKED_LIST
Maximum length of linked list, to make sure not to be able to use unlimited memory.
virtual ros::Time getLatestTimestamp()
void interpolate(const TransformStorage &one, const TransformStorage &two, ros::Time time, TransformStorage &output)
static const int64_t DEFAULT_MAX_STORAGE_TIME
default value of 10 seconds storage
virtual bool insertData(const TransformStorage &new_data, std::string *error_str=0)=0
virtual ros::Time getOldestTimestamp()=0
virtual unsigned int getListLength()
virtual P_TimeAndFrameID getLatestTimeAndParent()
uint8_t findClosest(TransformStorage *&one, TransformStorage *&two, ros::Time target_time, std::string *error_str)
L_TransformStorage storage_
virtual void clearList()=0
ROS_DECLARE_MESSAGE(TransformStamped)
virtual ros::Time getLatestTimestamp()=0
virtual bool getData(ros::Time time, TransformStorage &data_out, std::string *error_str=0)
virtual CompactFrameID getParent(ros::Time time, std::string *error_str)
std::pair< ros::Time, CompactFrameID > P_TimeAndFrameID
virtual ros::Time getLatestTimestamp()
virtual bool getData(ros::Time time, TransformStorage &data_out, std::string *error_str=0)=0
TimeCache(ros::Duration max_storage_time=ros::Duration().fromNSec(DEFAULT_MAX_STORAGE_TIME))
virtual P_TimeAndFrameID getLatestTimeAndParent()=0
virtual ros::Time getOldestTimestamp()
virtual P_TimeAndFrameID getLatestTimeAndParent()
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:12