$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00032 #include "tf/time_cache.h" 00033 #include "tf/exceptions.h" 00034 00035 #include "LinearMath/btTransform.h" 00036 #include <geometry_msgs/TransformStamped.h> 00037 00038 #include "ros/assert.h" 00039 00040 using namespace tf; 00041 00042 TransformStorage::TransformStorage() 00043 { 00044 } 00045 00046 TransformStorage::TransformStorage(const StampedTransform& data, CompactFrameID frame_id, 00047 CompactFrameID child_frame_id) 00048 : rotation_(data.getRotation()) 00049 , translation_(data.getOrigin()) 00050 , stamp_(data.stamp_) 00051 , frame_id_(frame_id) 00052 , child_frame_id_(child_frame_id) 00053 { } 00054 00055 TimeCache::TimeCache(ros::Duration max_storage_time) 00056 : max_storage_time_(max_storage_time) 00057 {} 00058 00059 // hoisting these into separate functions causes an ~8% speedup. Removing calling them altogether adds another ~10% 00060 void createEmptyException(std::string *error_str) 00061 { 00062 if (error_str) 00063 { 00064 *error_str = "Unable to lookup transform, cache is empty"; 00065 } 00066 } 00067 00068 void createExtrapolationException1(ros::Time t0, ros::Time t1, std::string* error_str) 00069 { 00070 if (error_str) 00071 { 00072 std::stringstream ss; 00073 ss << "Lookup would require extrapolation at time " << t0 << ", but only time " << t1 << " is in the buffer"; 00074 *error_str = ss.str(); 00075 } 00076 } 00077 00078 void createExtrapolationException2(ros::Time t0, ros::Time t1, std::string* error_str) 00079 { 00080 if (error_str) 00081 { 00082 std::stringstream ss; 00083 ss << "Lookup would require extrapolation into the future. Requested time " << t0 << " but the latest data is at time " << t1; 00084 *error_str = ss.str(); 00085 } 00086 } 00087 00088 void createExtrapolationException3(ros::Time t0, ros::Time t1, std::string* error_str) 00089 { 00090 if (error_str) 00091 { 00092 std::stringstream ss; 00093 ss << "Lookup would require extrapolation into the past. Requested time " << t0 << " but the earliest data is at time " << t1; 00094 *error_str = ss.str(); 00095 } 00096 } 00097 00098 uint8_t TimeCache::findClosest(TransformStorage*& one, TransformStorage*& two, ros::Time target_time, std::string* error_str) 00099 { 00100 //No values stored 00101 if (storage_.empty()) 00102 { 00103 createEmptyException(error_str); 00104 return 0; 00105 } 00106 00107 //If time == 0 return the latest 00108 if (target_time.isZero()) 00109 { 00110 one = &storage_.front(); 00111 return 1; 00112 } 00113 00114 // One value stored 00115 if (++storage_.begin() == storage_.end()) 00116 { 00117 TransformStorage& ts = *storage_.begin(); 00118 if (ts.stamp_ == target_time) 00119 { 00120 one = &ts; 00121 return 1; 00122 } 00123 else 00124 { 00125 createExtrapolationException1(target_time, ts.stamp_, error_str); 00126 return 0; 00127 } 00128 } 00129 00130 ros::Time latest_time = (*storage_.begin()).stamp_; 00131 ros::Time earliest_time = (*(storage_.rbegin())).stamp_; 00132 00133 if (target_time == latest_time) 00134 { 00135 one = &(*storage_.begin()); 00136 return 1; 00137 } 00138 else if (target_time == earliest_time) 00139 { 00140 one = &(*storage_.rbegin()); 00141 return 1; 00142 } 00143 // Catch cases that would require extrapolation 00144 else if (target_time > latest_time) 00145 { 00146 createExtrapolationException2(target_time, latest_time, error_str); 00147 return 0; 00148 } 00149 else if (target_time < earliest_time) 00150 { 00151 createExtrapolationException3(target_time, earliest_time, error_str); 00152 return 0; 00153 } 00154 00155 //At least 2 values stored 00156 //Find the first value less than the target value 00157 L_TransformStorage::iterator storage_it = storage_.begin(); 00158 while(storage_it != storage_.end()) 00159 { 00160 if (storage_it->stamp_ <= target_time) 00161 break; 00162 storage_it++; 00163 } 00164 00165 //Finally the case were somewhere in the middle Guarenteed no extrapolation :-) 00166 one = &*(storage_it); //Older 00167 two = &*(--storage_it); //Newer 00168 return 2; 00169 00170 00171 } 00172 00173 void TimeCache::interpolate(const TransformStorage& one, const TransformStorage& two, ros::Time time, TransformStorage& output) 00174 { 00175 // Check for zero distance case 00176 if( two.stamp_ == one.stamp_ ) 00177 { 00178 output = two; 00179 return; 00180 } 00181 //Calculate the ratio 00182 btScalar ratio = (time.toSec() - one.stamp_.toSec()) / (two.stamp_.toSec() - one.stamp_.toSec()); 00183 00184 //Interpolate translation 00185 output.translation_.setInterpolate3(one.translation_, two.translation_, ratio); 00186 00187 //Interpolate rotation 00188 output.rotation_ = slerp( one.rotation_, two.rotation_, ratio); 00189 00190 output.stamp_ = one.stamp_; 00191 output.frame_id_ = one.frame_id_; 00192 output.child_frame_id_ = one.child_frame_id_; 00193 } 00194 00195 bool TimeCache::getData(ros::Time time, TransformStorage & data_out, std::string* error_str) //returns false if data not available 00196 { 00197 TransformStorage* p_temp_1 = NULL; 00198 TransformStorage* p_temp_2 = NULL; 00199 00200 int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str); 00201 if (num_nodes == 0) 00202 { 00203 return false; 00204 } 00205 else if (num_nodes == 1) 00206 { 00207 data_out = *p_temp_1; 00208 } 00209 else if (num_nodes == 2) 00210 { 00211 if( p_temp_1->frame_id_ == p_temp_2->frame_id_) 00212 { 00213 interpolate(*p_temp_1, *p_temp_2, time, data_out); 00214 } 00215 else 00216 { 00217 data_out = *p_temp_1; 00218 } 00219 } 00220 else 00221 { 00222 ROS_BREAK(); 00223 } 00224 00225 return true; 00226 } 00227 00228 CompactFrameID TimeCache::getParent(ros::Time time, std::string* error_str) 00229 { 00230 TransformStorage* p_temp_1 = NULL; 00231 TransformStorage* p_temp_2 = NULL; 00232 00233 int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str); 00234 if (num_nodes == 0) 00235 { 00236 return 0; 00237 } 00238 00239 return p_temp_1->frame_id_; 00240 } 00241 00242 bool TimeCache::insertData(const TransformStorage& new_data) 00243 { 00244 L_TransformStorage::iterator storage_it = storage_.begin(); 00245 00246 if(storage_it != storage_.end()) 00247 { 00248 if (storage_it->stamp_ > new_data.stamp_ + max_storage_time_) 00249 { 00250 return false; 00251 } 00252 } 00253 00254 00255 while(storage_it != storage_.end()) 00256 { 00257 if (storage_it->stamp_ <= new_data.stamp_) 00258 break; 00259 storage_it++; 00260 } 00261 storage_.insert(storage_it, new_data); 00262 00263 pruneList(); 00264 return true; 00265 } 00266 00267 void TimeCache::clearList() 00268 { 00269 storage_.clear(); 00270 } 00271 00272 unsigned int TimeCache::getListLength() 00273 { 00274 return storage_.size(); 00275 } 00276 00277 P_TimeAndFrameID TimeCache::getLatestTimeAndParent() 00278 { 00279 if (storage_.empty()) 00280 { 00281 return std::make_pair(ros::Time(), 0); 00282 } 00283 00284 const TransformStorage& ts = storage_.front(); 00285 return std::make_pair(ts.stamp_, ts.frame_id_); 00286 } 00287 00288 ros::Time TimeCache::getLatestTimestamp() 00289 { 00290 if (storage_.empty()) return ros::Time(); //empty list case 00291 return storage_.front().stamp_; 00292 } 00293 00294 ros::Time TimeCache::getOldestTimestamp() 00295 { 00296 if (storage_.empty()) return ros::Time(); //empty list case 00297 return storage_.back().stamp_; 00298 } 00299 00300 void TimeCache::pruneList() 00301 { 00302 ros::Time latest_time = storage_.begin()->stamp_; 00303 00304 while(!storage_.empty() && storage_.back().stamp_ + max_storage_time_ < latest_time) 00305 { 00306 storage_.pop_back(); 00307 } 00308 00309 }