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