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 #include "tf2/time_cache.h"
00033 #include "tf2/exceptions.h"
00034
00035 #include <tf2/LinearMath/Vector3.h>
00036 #include <tf2/LinearMath/Quaternion.h>
00037 #include <tf2/LinearMath/Transform.h>
00038 #include <geometry_msgs/TransformStamped.h>
00039 #include <assert.h>
00040
00041 namespace tf2 {
00042
00043 TransformStorage::TransformStorage()
00044 {
00045 }
00046
00047 TransformStorage::TransformStorage(const geometry_msgs::TransformStamped& data, CompactFrameID frame_id,
00048 CompactFrameID child_frame_id)
00049 : stamp_(data.header.stamp)
00050 , frame_id_(frame_id)
00051 , child_frame_id_(child_frame_id)
00052 {
00053 const geometry_msgs::Quaternion& o = data.transform.rotation;
00054 rotation_ = tf2::Quaternion(o.x, o.y, o.z, o.w);
00055 const geometry_msgs::Vector3& v = data.transform.translation;
00056 translation_ = tf2::Vector3(v.x, v.y, v.z);
00057 }
00058
00059 TimeCache::TimeCache(ros::Duration max_storage_time)
00060 : max_storage_time_(max_storage_time)
00061 {}
00062
00063 namespace cache {
00064
00065 void createExtrapolationException1(ros::Time t0, ros::Time t1, std::string* error_str)
00066 {
00067 if (error_str)
00068 {
00069 std::stringstream ss;
00070 ss << "Lookup would require extrapolation at time " << t0 << ", but only time " << t1 << " is in the buffer";
00071 *error_str = ss.str();
00072 }
00073 }
00074
00075 void createExtrapolationException2(ros::Time t0, ros::Time t1, std::string* error_str)
00076 {
00077 if (error_str)
00078 {
00079 std::stringstream ss;
00080 ss << "Lookup would require extrapolation into the future. Requested time " << t0 << " but the latest data is at time " << t1;
00081 *error_str = ss.str();
00082 }
00083 }
00084
00085 void createExtrapolationException3(ros::Time t0, ros::Time t1, std::string* error_str)
00086 {
00087 if (error_str)
00088 {
00089 std::stringstream ss;
00090 ss << "Lookup would require extrapolation into the past. Requested time " << t0 << " but the earliest data is at time " << t1;
00091 *error_str = ss.str();
00092 }
00093 }
00094 }
00095
00096 bool operator>(const TransformStorage& lhs, const TransformStorage& rhs)
00097 {
00098 return lhs.stamp_ > rhs.stamp_;
00099 }
00100
00101 uint8_t TimeCache::findClosest(TransformStorage*& one, TransformStorage*& two, ros::Time target_time, std::string* error_str)
00102 {
00103
00104 if (storage_.empty())
00105 {
00106 return 0;
00107 }
00108
00109
00110 if (target_time.isZero())
00111 {
00112 one = &storage_.front();
00113 return 1;
00114 }
00115
00116
00117 if (++storage_.begin() == storage_.end())
00118 {
00119 TransformStorage& ts = *storage_.begin();
00120 if (ts.stamp_ == target_time)
00121 {
00122 one = &ts;
00123 return 1;
00124 }
00125 else
00126 {
00127 cache::createExtrapolationException1(target_time, ts.stamp_, error_str);
00128 return 0;
00129 }
00130 }
00131
00132 ros::Time latest_time = (*storage_.begin()).stamp_;
00133 ros::Time earliest_time = (*(storage_.rbegin())).stamp_;
00134
00135 if (target_time == latest_time)
00136 {
00137 one = &(*storage_.begin());
00138 return 1;
00139 }
00140 else if (target_time == earliest_time)
00141 {
00142 one = &(*storage_.rbegin());
00143 return 1;
00144 }
00145
00146 else if (target_time > latest_time)
00147 {
00148 cache::createExtrapolationException2(target_time, latest_time, error_str);
00149 return 0;
00150 }
00151 else if (target_time < earliest_time)
00152 {
00153 cache::createExtrapolationException3(target_time, earliest_time, error_str);
00154 return 0;
00155 }
00156
00157
00158
00159 L_TransformStorage::iterator storage_it;
00160 TransformStorage storage_target_time;
00161 storage_target_time.stamp_ = target_time;
00162
00163 storage_it = std::lower_bound(
00164 storage_.begin(),
00165 storage_.end(),
00166 storage_target_time, std::greater<TransformStorage>());
00167
00168
00169 one = &*(storage_it);
00170 two = &*(--storage_it);
00171 return 2;
00172
00173
00174 }
00175
00176 void TimeCache::interpolate(const TransformStorage& one, const TransformStorage& two, ros::Time time, TransformStorage& output)
00177 {
00178
00179 if( two.stamp_ == one.stamp_ )
00180 {
00181 output = two;
00182 return;
00183 }
00184
00185 tf2Scalar ratio = (time - one.stamp_).toSec() / (two.stamp_ - one.stamp_).toSec();
00186
00187
00188 output.translation_.setInterpolate3(one.translation_, two.translation_, ratio);
00189
00190
00191 output.rotation_ = slerp( one.rotation_, two.rotation_, ratio);
00192
00193 output.stamp_ = time;
00194 output.frame_id_ = one.frame_id_;
00195 output.child_frame_id_ = one.child_frame_id_;
00196 }
00197
00198 bool TimeCache::getData(ros::Time time, TransformStorage & data_out, std::string* error_str)
00199 {
00200 TransformStorage* p_temp_1;
00201 TransformStorage* p_temp_2;
00202
00203 int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str);
00204 if (num_nodes == 0)
00205 {
00206 return false;
00207 }
00208 else if (num_nodes == 1)
00209 {
00210 data_out = *p_temp_1;
00211 }
00212 else if (num_nodes == 2)
00213 {
00214 if( p_temp_1->frame_id_ == p_temp_2->frame_id_)
00215 {
00216 interpolate(*p_temp_1, *p_temp_2, time, data_out);
00217 }
00218 else
00219 {
00220 data_out = *p_temp_1;
00221 }
00222 }
00223 else
00224 {
00225 assert(0);
00226 }
00227
00228 return true;
00229 }
00230
00231 CompactFrameID TimeCache::getParent(ros::Time time, std::string* error_str)
00232 {
00233 TransformStorage* p_temp_1;
00234 TransformStorage* p_temp_2;
00235
00236 int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str);
00237 if (num_nodes == 0)
00238 {
00239 return 0;
00240 }
00241
00242 return p_temp_1->frame_id_;
00243 }
00244
00245 bool TimeCache::insertData(const TransformStorage& new_data)
00246 {
00247 L_TransformStorage::iterator storage_it = storage_.begin();
00248
00249 if(storage_it != storage_.end())
00250 {
00251 if (storage_it->stamp_ > new_data.stamp_ + max_storage_time_)
00252 {
00253 return false;
00254 }
00255 }
00256
00257
00258 while(storage_it != storage_.end())
00259 {
00260 if (storage_it->stamp_ <= new_data.stamp_)
00261 break;
00262 storage_it++;
00263 }
00264 storage_.insert(storage_it, new_data);
00265
00266 pruneList();
00267 return true;
00268 }
00269
00270 void TimeCache::clearList()
00271 {
00272 storage_.clear();
00273 }
00274
00275 unsigned int TimeCache::getListLength()
00276 {
00277 return storage_.size();
00278 }
00279
00280 P_TimeAndFrameID TimeCache::getLatestTimeAndParent()
00281 {
00282 if (storage_.empty())
00283 {
00284 return std::make_pair(ros::Time(), 0);
00285 }
00286
00287 const TransformStorage& ts = storage_.front();
00288 return std::make_pair(ts.stamp_, ts.frame_id_);
00289 }
00290
00291 ros::Time TimeCache::getLatestTimestamp()
00292 {
00293 if (storage_.empty()) return ros::Time();
00294 return storage_.front().stamp_;
00295 }
00296
00297 ros::Time TimeCache::getOldestTimestamp()
00298 {
00299 if (storage_.empty()) return ros::Time();
00300 return storage_.back().stamp_;
00301 }
00302
00303 void TimeCache::pruneList()
00304 {
00305 ros::Time latest_time = storage_.begin()->stamp_;
00306
00307 while(!storage_.empty() && storage_.back().stamp_ + max_storage_time_ < latest_time)
00308 {
00309 storage_.pop_back();
00310 }
00311
00312 }
00313 }