cache.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #include "tf2/time_cache.h"
33 #include "tf2/exceptions.h"
34 
35 #include <tf2/LinearMath/Vector3.h>
38 #include <geometry_msgs/TransformStamped.h>
39 #include <assert.h>
40 
41 namespace tf2 {
42 
44 {
45 }
46 
47 TransformStorage::TransformStorage(const geometry_msgs::TransformStamped& data, CompactFrameID frame_id,
48  CompactFrameID child_frame_id)
49 : stamp_(data.header.stamp)
50 , frame_id_(frame_id)
51 , child_frame_id_(child_frame_id)
52 {
53  const geometry_msgs::Quaternion& o = data.transform.rotation;
54  rotation_ = tf2::Quaternion(o.x, o.y, o.z, o.w);
55  const geometry_msgs::Vector3& v = data.transform.translation;
56  translation_ = tf2::Vector3(v.x, v.y, v.z);
57 }
58 
60 : max_storage_time_(max_storage_time)
61 {}
62 
63 namespace cache { // Avoid ODR collisions https://github.com/ros/geometry2/issues/175
64 // hoisting these into separate functions causes an ~8% speedup. Removing calling them altogether adds another ~10%
65 void createExtrapolationException1(ros::Time t0, ros::Time t1, std::string* error_str)
66 {
67  if (error_str)
68  {
69  char str[117]; // Text without formatting strings has 77, each timestamp has up to 20
70  snprintf(str, sizeof(str), "Lookup would require extrapolation at time %.09f, but only time %.09f is in the buffer", t0.toSec(), t1.toSec());
71  *error_str = str;
72  }
73 }
74 
75 void createExtrapolationException2(ros::Time t0, ros::Time t1, std::string* error_str)
76 {
77  if (error_str)
78  {
79  // Want this to come out positive, because this is a future extrapolation problem with t0
80  // t0 needs to come first because it will be bigger than t1
81  ros::Duration tdiff = t0 - t1;
82  char str[163]; // Text without formatting strings has 102, each timestamp has up to 20
83  snprintf(
84  str, sizeof(str),
85  "Lookup would require extrapolation %.09fs into the future. Requested time %.09f but the latest data is at time %.09f",
86  tdiff.toSec(), t0.toSec(), t1.toSec());
87  *error_str = str;
88  }
89 }
90 
91 void createExtrapolationException3(ros::Time t0, ros::Time t1, std::string* error_str)
92 {
93  if (error_str)
94  {
95  ros::Duration tdiff = t1 - t0;
96  char str[163]; // Text without formatting strings has 102, each timestamp has up to 20
97  snprintf(
98  str, sizeof(str),
99  "Lookup would require extrapolation %.09fs into the past. Requested time %.09f but the earliest data is at time %.09f",
100  tdiff.toSec(), t0.toSec(), t1.toSec());
101  *error_str = str;
102  }
103 }
104 } // namespace cache
105 
106 bool operator>(const TransformStorage& lhs, const TransformStorage& rhs)
107 {
108  return lhs.stamp_ > rhs.stamp_;
109 }
110 
111 uint8_t TimeCache::findClosest(TransformStorage*& one, TransformStorage*& two, ros::Time target_time, std::string* error_str)
112 {
113  //No values stored
114  if (storage_.empty())
115  {
116  return 0;
117  }
118 
119  //If time == 0 return the latest
120  if (target_time.isZero())
121  {
122  one = &storage_.front();
123  return 1;
124  }
125 
126  // One value stored
127  if (++storage_.begin() == storage_.end())
128  {
129  TransformStorage& ts = *storage_.begin();
130  if (ts.stamp_ == target_time)
131  {
132  one = &ts;
133  return 1;
134  }
135  else
136  {
137  cache::createExtrapolationException1(target_time, ts.stamp_, error_str);
138  return 0;
139  }
140  }
141 
142  ros::Time latest_time = (*storage_.begin()).stamp_;
143  ros::Time earliest_time = (*(storage_.rbegin())).stamp_;
144 
145  if (target_time == latest_time)
146  {
147  one = &(*storage_.begin());
148  return 1;
149  }
150  else if (target_time == earliest_time)
151  {
152  one = &(*storage_.rbegin());
153  return 1;
154  }
155  // Catch cases that would require extrapolation
156  else if (target_time > latest_time)
157  {
158  cache::createExtrapolationException2(target_time, latest_time, error_str);
159  return 0;
160  }
161  else if (target_time < earliest_time)
162  {
163  cache::createExtrapolationException3(target_time, earliest_time, error_str);
164  return 0;
165  }
166 
167  //At least 2 values stored
168  //Find the first value less than the target value
169  L_TransformStorage::iterator storage_it;
170  TransformStorage storage_target_time;
171  storage_target_time.stamp_ = target_time;
172 
173  storage_it = std::lower_bound(
174  storage_.begin(),
175  storage_.end(),
176  storage_target_time, std::greater<TransformStorage>());
177 
178  //Finally the case were somewhere in the middle Guarenteed no extrapolation :-)
179  one = &*(storage_it); //Older
180  two = &*(--storage_it); //Newer
181  return 2;
182 
183 
184 }
185 
187 {
188  // Check for zero distance case
189  if( two.stamp_ == one.stamp_ )
190  {
191  output = two;
192  return;
193  }
194  //Calculate the ratio
195  tf2Scalar ratio = (time - one.stamp_).toSec() / (two.stamp_ - one.stamp_).toSec();
196 
197  //Interpolate translation
198  output.translation_.setInterpolate3(one.translation_, two.translation_, ratio);
199 
200  //Interpolate rotation
201  output.rotation_ = slerp( one.rotation_, two.rotation_, ratio);
202 
203  output.stamp_ = time;
204  output.frame_id_ = one.frame_id_;
205  output.child_frame_id_ = one.child_frame_id_;
206 }
207 
208 bool TimeCache::getData(ros::Time time, TransformStorage & data_out, std::string* error_str) //returns false if data not available
209 {
210  TransformStorage* p_temp_1;
211  TransformStorage* p_temp_2;
212 
213  int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str);
214  if (num_nodes == 0)
215  {
216  return false;
217  }
218  else if (num_nodes == 1)
219  {
220  data_out = *p_temp_1;
221  }
222  else if (num_nodes == 2)
223  {
224  if( p_temp_1->frame_id_ == p_temp_2->frame_id_)
225  {
226  interpolate(*p_temp_1, *p_temp_2, time, data_out);
227  }
228  else
229  {
230  data_out = *p_temp_1;
231  }
232  }
233  else
234  {
235  assert(0);
236  }
237 
238  return true;
239 }
240 
241 CompactFrameID TimeCache::getParent(ros::Time time, std::string* error_str)
242 {
243  TransformStorage* p_temp_1;
244  TransformStorage* p_temp_2;
245 
246  int num_nodes = findClosest(p_temp_1, p_temp_2, time, error_str);
247  if (num_nodes == 0)
248  {
249  return 0;
250  }
251 
252  return p_temp_1->frame_id_;
253 }
254 
255 bool TimeCache::insertData(const TransformStorage& new_data, std::string* error_str)
256 {
257  L_TransformStorage::iterator storage_it = storage_.begin();
258 
259  if(storage_it != storage_.end())
260  {
261  if (storage_it->stamp_ > new_data.stamp_ + max_storage_time_)
262  {
263  if (error_str)
264  {
265  *error_str = "TF_OLD_DATA ignoring data from the past (Possible reasons are listed at http://wiki.ros.org/tf/Errors%%20explained)";
266  }
267  return false;
268  }
269  }
270 
271 
272  while(storage_it != storage_.end())
273  {
274  if (storage_it->stamp_ <= new_data.stamp_)
275  break;
276  storage_it++;
277  }
278  if (storage_it != storage_.end() && storage_it->stamp_ == new_data.stamp_)
279  {
280  if (error_str)
281  {
282  *error_str = "TF_REPEATED_DATA ignoring data with redundant timestamp";
283  }
284  return false;
285  }
286  else
287  {
288  storage_.insert(storage_it, new_data);
289  }
290 
291  pruneList();
292  return true;
293 }
294 
296 {
297  storage_.clear();
298 }
299 
301 {
302  return storage_.size();
303 }
304 
306 {
307  if (storage_.empty())
308  {
309  return std::make_pair(ros::Time(), 0);
310  }
311 
312  const TransformStorage& ts = storage_.front();
313  return std::make_pair(ts.stamp_, ts.frame_id_);
314 }
315 
317 {
318  if (storage_.empty()) return ros::Time(); //empty list case
319  return storage_.front().stamp_;
320 }
321 
323 {
324  if (storage_.empty()) return ros::Time(); //empty list case
325  return storage_.back().stamp_;
326 }
327 
329 {
330  ros::Time latest_time = storage_.begin()->stamp_;
331 
332  while(!storage_.empty() && storage_.back().stamp_ + max_storage_time_ < latest_time)
333  {
334  storage_.pop_back();
335  }
336 
337 } // namespace tf2
338 }
tf2::TimeCache::max_storage_time_
ros::Duration max_storage_time_
Definition: time_cache.h:120
tf2::TransformStorage::TransformStorage
TransformStorage()
Definition: cache.cpp:43
tf2::TimeCache::getOldestTimestamp
virtual ros::Time getOldestTimestamp()
Get the oldest timestamp cached.
Definition: cache.cpp:322
exceptions.h
Transform.h
TimeBase< Time, Duration >::toSec
double toSec() const
tf2::TransformStorage::child_frame_id_
CompactFrameID child_frame_id_
Definition: transform_storage.h:80
tf2::TimeCache::insertData
virtual bool insertData(const TransformStorage &new_data, std::string *error_str=0)
Insert data into the cache.
Definition: cache.cpp:255
tf2::TimeCache::clearList
virtual void clearList()
Clear the list of stored values.
Definition: cache.cpp:295
tf2::TimeCache::pruneList
void pruneList()
Definition: cache.cpp:328
tf2::CompactFrameID
uint32_t CompactFrameID
Definition: transform_storage.h:50
tf2::TimeCache::getParent
virtual CompactFrameID getParent(ros::Time time, std::string *error_str)
Retrieve the parent at a specific time.
Definition: cache.cpp:241
tf2::TransformStorage::rotation_
tf2::Quaternion rotation_
Definition: transform_storage.h:76
tf2::TransformStorage
Storage for transforms and their parent.
Definition: transform_storage.h:53
tf2::TimeCache::interpolate
void interpolate(const TransformStorage &one, const TransformStorage &two, ros::Time time, TransformStorage &output)
Definition: cache.cpp:186
tf2::TimeCache::getListLength
virtual unsigned int getListLength()
Debugging information methods.
Definition: cache.cpp:300
TimeBase< Time, Duration >::isZero
bool isZero() const
tf2::operator>
bool operator>(const TransformStorage &lhs, const TransformStorage &rhs)
Definition: cache.cpp:106
tf2::TimeCache::findClosest
uint8_t findClosest(TransformStorage *&one, TransformStorage *&two, ros::Time target_time, std::string *error_str)
A helper function for getData.
Definition: cache.cpp:111
tf2::TimeCache::storage_
L_TransformStorage storage_
Definition: time_cache.h:118
tf2::TransformStorage::stamp_
ros::Time stamp_
Definition: transform_storage.h:78
Quaternion.h
time_cache.h
tf2::TransformStorage::translation_
tf2::Vector3 translation_
Definition: transform_storage.h:77
tf2::TransformStorage::frame_id_
CompactFrameID frame_id_
Definition: transform_storage.h:79
tf2::cache::createExtrapolationException1
void createExtrapolationException1(ros::Time t0, ros::Time t1, std::string *error_str)
Definition: cache.cpp:65
tf2::TimeCache::getData
virtual bool getData(ros::Time time, TransformStorage &data_out, std::string *error_str=0)
Virtual methods.
Definition: cache.cpp:208
header
std_msgs::Header const * header(const M &m)
tf2::P_TimeAndFrameID
std::pair< ros::Time, CompactFrameID > P_TimeAndFrameID
Definition: buffer_core.h:57
tf2::TimeCache::getLatestTimestamp
virtual ros::Time getLatestTimestamp()
Get the latest timestamp cached.
Definition: cache.cpp:316
ros::Time
tf2::cache::createExtrapolationException3
void createExtrapolationException3(ros::Time t0, ros::Time t1, std::string *error_str)
Definition: cache.cpp:91
Vector3.h
tf2
Definition: buffer_core.h:54
tf2::TimeCache::TimeCache
TimeCache(ros::Duration max_storage_time=ros::Duration().fromNSec(DEFAULT_MAX_STORAGE_TIME))
Definition: cache.cpp:59
tf2::Quaternion
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
tf2::slerp
TF2SIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t)
Return the result of spherical linear interpolation betwen two quaternions.
Definition: Quaternion.h:432
DurationBase< Duration >::toSec
double toSec() const
tf2Scalar
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
Definition: Scalar.h:159
tf2::TimeCache::getLatestTimeAndParent
virtual P_TimeAndFrameID getLatestTimeAndParent()
Get the latest time stored in this cache, and the parent associated with it. Returns parent = 0 if no...
Definition: cache.cpp:305
ros::Duration
tf2::cache::createExtrapolationException2
void createExtrapolationException2(ros::Time t0, ros::Time t1, std::string *error_str)
Definition: cache.cpp:75


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:11