Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00032 #ifndef TF2_TIME_CACHE_H
00033 #define TF2_TIME_CACHE_H
00034
00035 #include "transform_storage.h"
00036
00037 #include <list>
00038
00039 #include <sstream>
00040
00041 #include <ros/message_forward.h>
00042 #include <ros/time.h>
00043
00044 namespace geometry_msgs
00045 {
00046 ROS_DECLARE_MESSAGE(TransformStamped);
00047 }
00048
00049 namespace tf2
00050 {
00051
00052 typedef std::pair<ros::Time, CompactFrameID> P_TimeAndFrameID;
00053
00054 class TimeCacheInterface
00055 {
00056 public:
00058 virtual bool getData(ros::Time time, TransformStorage & data_out, std::string* error_str = 0)=0;
00059
00061 virtual bool insertData(const TransformStorage& new_data)=0;
00062
00064 virtual void clearList()=0;
00065
00067 virtual CompactFrameID getParent(ros::Time time, std::string* error_str) = 0;
00068
00072 virtual P_TimeAndFrameID getLatestTimeAndParent() = 0;
00073
00074
00076
00077 virtual unsigned int getListLength()=0;
00078
00080 virtual ros::Time getLatestTimestamp()=0;
00081
00083 virtual ros::Time getOldestTimestamp()=0;
00084 };
00085
00086
00091 class TimeCache : public TimeCacheInterface
00092 {
00093 public:
00094 static const int MIN_INTERPOLATION_DISTANCE = 5;
00095 static const unsigned int MAX_LENGTH_LINKED_LIST = 1000000;
00096 static const int64_t DEFAULT_MAX_STORAGE_TIME = 1ULL * 1000000000LL;
00097
00098 TimeCache(ros::Duration max_storage_time = ros::Duration().fromNSec(DEFAULT_MAX_STORAGE_TIME));
00099
00100
00102
00103 virtual bool getData(ros::Time time, TransformStorage & data_out, std::string* error_str = 0);
00104 virtual bool insertData(const TransformStorage& new_data);
00105 virtual void clearList();
00106 virtual CompactFrameID getParent(ros::Time time, std::string* error_str);
00107 virtual P_TimeAndFrameID getLatestTimeAndParent();
00108
00110 virtual unsigned int getListLength();
00111 virtual ros::Time getLatestTimestamp();
00112 virtual ros::Time getOldestTimestamp();
00113
00114
00115 private:
00116 typedef std::list<TransformStorage> L_TransformStorage;
00117 L_TransformStorage storage_;
00118
00119 ros::Duration max_storage_time_;
00120
00121
00123
00124 inline uint8_t findClosest(TransformStorage*& one, TransformStorage*& two, ros::Time target_time, std::string* error_str);
00125
00126 inline void interpolate(const TransformStorage& one, const TransformStorage& two, ros::Time time, TransformStorage& output);
00127
00128
00129 void pruneList();
00130
00131
00132
00133 };
00134
00135 class StaticCache : public TimeCacheInterface
00136 {
00137 public:
00139
00140 virtual bool getData(ros::Time time, TransformStorage & data_out, std::string* error_str = 0);
00141 virtual bool insertData(const TransformStorage& new_data);
00142 virtual void clearList();
00143 virtual CompactFrameID getParent(ros::Time time, std::string* error_str);
00144 virtual P_TimeAndFrameID getLatestTimeAndParent();
00145
00146
00148 virtual unsigned int getListLength();
00149 virtual ros::Time getLatestTimestamp();
00150 virtual ros::Time getOldestTimestamp();
00151
00152
00153 private:
00154 TransformStorage storage_;
00155 };
00156
00157 }
00158
00159 #endif // TF2_TIME_CACHE_H