cache.cpp
Go to the documentation of this file.
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 "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 { // Avoid ODR collisions https://github.com/ros/geometry2/issues/175 
00064 // hoisting these into separate functions causes an ~8% speedup.  Removing calling them altogether adds another ~10%
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 } // namespace cache
00095 
00096 uint8_t TimeCache::findClosest(TransformStorage*& one, TransformStorage*& two, ros::Time target_time, std::string* error_str)
00097 {
00098   //No values stored
00099   if (storage_.empty())
00100   {
00101     return 0;
00102   }
00103 
00104   //If time == 0 return the latest
00105   if (target_time.isZero())
00106   {
00107     one = &storage_.front();
00108     return 1;
00109   }
00110 
00111   // One value stored
00112   if (++storage_.begin() == storage_.end())
00113   {
00114     TransformStorage& ts = *storage_.begin();
00115     if (ts.stamp_ == target_time)
00116     {
00117       one = &ts;
00118       return 1;
00119     }
00120     else
00121     {
00122       cache::createExtrapolationException1(target_time, ts.stamp_, error_str);
00123       return 0;
00124     }
00125   }
00126 
00127   ros::Time latest_time = (*storage_.begin()).stamp_;
00128   ros::Time earliest_time = (*(storage_.rbegin())).stamp_;
00129 
00130   if (target_time == latest_time)
00131   {
00132     one = &(*storage_.begin());
00133     return 1;
00134   }
00135   else if (target_time == earliest_time)
00136   {
00137     one = &(*storage_.rbegin());
00138     return 1;
00139   }
00140   // Catch cases that would require extrapolation
00141   else if (target_time > latest_time)
00142   {
00143     cache::createExtrapolationException2(target_time, latest_time, error_str);
00144     return 0;
00145   }
00146   else if (target_time < earliest_time)
00147   {
00148     cache::createExtrapolationException3(target_time, earliest_time, error_str);
00149     return 0;
00150   }
00151 
00152   //At least 2 values stored
00153   //Find the first value less than the target value
00154   L_TransformStorage::iterator storage_it = storage_.begin();
00155   while(storage_it != storage_.end())
00156   {
00157     if (storage_it->stamp_ <= target_time)
00158       break;
00159     storage_it++;
00160   }
00161 
00162   //Finally the case were somewhere in the middle  Guarenteed no extrapolation :-)
00163   one = &*(storage_it); //Older
00164   two = &*(--storage_it); //Newer
00165   return 2;
00166 
00167 
00168 }
00169 
00170 void TimeCache::interpolate(const TransformStorage& one, const TransformStorage& two, ros::Time time, TransformStorage& output)
00171 {
00172   // Check for zero distance case
00173   if( two.stamp_ == one.stamp_ )
00174   {
00175     output = two;
00176     return;
00177   }
00178   //Calculate the ratio
00179   tf2Scalar ratio = (time.toSec() - one.stamp_.toSec()) / (two.stamp_.toSec() - one.stamp_.toSec());
00180 
00181   //Interpolate translation
00182   output.translation_.setInterpolate3(one.translation_, two.translation_, ratio);
00183 
00184   //Interpolate rotation
00185   output.rotation_ = slerp( one.rotation_, two.rotation_, ratio);
00186 
00187   output.stamp_ = one.stamp_;
00188   output.frame_id_ = one.frame_id_;
00189   output.child_frame_id_ = one.child_frame_id_;
00190 }
00191 
00192 bool TimeCache::getData(ros::Time time, TransformStorage & data_out, std::string* error_str) //returns false if data not available
00193 {
00194   TransformStorage* p_temp_1;
00195   TransformStorage* p_temp_2;
00196 
00197   int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str);
00198   if (num_nodes == 0)
00199   {
00200     return false;
00201   }
00202   else if (num_nodes == 1)
00203   {
00204     data_out = *p_temp_1;
00205   }
00206   else if (num_nodes == 2)
00207   {
00208     if( p_temp_1->frame_id_ == p_temp_2->frame_id_)
00209     {
00210       interpolate(*p_temp_1, *p_temp_2, time, data_out);
00211     }
00212     else
00213     {
00214       data_out = *p_temp_1;
00215     }
00216   }
00217   else
00218   {
00219     assert(0);
00220   }
00221 
00222   return true;
00223 }
00224 
00225 CompactFrameID TimeCache::getParent(ros::Time time, std::string* error_str)
00226 {
00227   TransformStorage* p_temp_1;
00228   TransformStorage* p_temp_2;
00229 
00230   int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str);
00231   if (num_nodes == 0)
00232   {
00233     return 0;
00234   }
00235 
00236   return p_temp_1->frame_id_;
00237 }
00238 
00239 bool TimeCache::insertData(const TransformStorage& new_data)
00240 {
00241   L_TransformStorage::iterator storage_it = storage_.begin();
00242 
00243   if(storage_it != storage_.end())
00244   {
00245     if (storage_it->stamp_ > new_data.stamp_ + max_storage_time_)
00246     {
00247       return false;
00248     }
00249   }
00250 
00251 
00252   while(storage_it != storage_.end())
00253   {
00254     if (storage_it->stamp_ <= new_data.stamp_)
00255       break;
00256     storage_it++;
00257   }
00258   storage_.insert(storage_it, new_data);
00259 
00260   pruneList();
00261   return true;
00262 }
00263 
00264 void TimeCache::clearList()
00265 {
00266   storage_.clear();
00267 }
00268 
00269 unsigned int TimeCache::getListLength()
00270 {
00271   return storage_.size();
00272 }
00273 
00274 P_TimeAndFrameID TimeCache::getLatestTimeAndParent()
00275 {
00276   if (storage_.empty())
00277   {
00278     return std::make_pair(ros::Time(), 0);
00279   }
00280 
00281   const TransformStorage& ts = storage_.front();
00282   return std::make_pair(ts.stamp_, ts.frame_id_);
00283 }
00284 
00285 ros::Time TimeCache::getLatestTimestamp() 
00286 {   
00287   if (storage_.empty()) return ros::Time(); //empty list case
00288   return storage_.front().stamp_;
00289 }
00290 
00291 ros::Time TimeCache::getOldestTimestamp() 
00292 {   
00293   if (storage_.empty()) return ros::Time(); //empty list case
00294   return storage_.back().stamp_;
00295 }
00296 
00297 void TimeCache::pruneList()
00298 {
00299   ros::Time latest_time = storage_.begin()->stamp_;
00300   
00301   while(!storage_.empty() && storage_.back().stamp_ + max_storage_time_ < latest_time)
00302   {
00303     storage_.pop_back();
00304   }
00305   
00306 } // namespace tf2
00307 }


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 2 2017 02:24:34