cache_unittest.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 
30 #include <ctime>
31 #include <cstdlib>
32 #include <gtest/gtest.h>
33 #include <tf/tf.h>
34 #include "tf/LinearMath/Vector3.h"
36 
37 
38 void seed_rand()
39 {
40  //Seed random number generator with current microseond count
41  std::srand(std::time(0));
42 }
43 
44 using namespace tf;
45 
46 
47 TEST(TimeCache, Repeatability)
48 {
49  unsigned int runs = 100;
50 
51  seed_rand();
52 
53  tf::TimeCache cache;
54  std::vector<double> values(runs);
55 
57  t.setIdentity();
58 
59  for ( uint64_t i = 1; i < runs ; i++ )
60  {
61  values[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
62  std::stringstream ss;
63  ss << values[i];
64  t.frame_id_ = ss.str();
65  t.stamp_ = ros::Time().fromNSec(i);
66 
67  TransformStorage stor(t, i, 0);
68 
69  cache.insertData(stor);
70  }
71 
72  TransformStorage out;
73  for ( uint64_t i = 1; i < runs ; i++ )
74  {
75  cache.getData(ros::Time().fromNSec(i), out);
76  EXPECT_EQ(out.frame_id_, i);
77  EXPECT_EQ(out.stamp_, ros::Time().fromNSec(i));
78  }
79 
80 }
81 
82 
83 TEST(TimeCache, RepeatabilityReverseInsertOrder)
84 {
85  unsigned int runs = 100;
86 
87  seed_rand();
88 
89  tf::TimeCache cache;
90  std::vector<double> values(runs);
91 
93  t.setIdentity();
94 
95  for ( int i = runs -1; i >= 0 ; i-- )
96  {
97  values[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
98  t.stamp_ = ros::Time().fromNSec(i);
99 
100  TransformStorage stor(t, i, 0);
101 
102  cache.insertData(stor);
103  }
104 
105  TransformStorage out;
106  for ( uint64_t i = 1; i < runs ; i++ )
107  {
108  cache.getData(ros::Time().fromNSec(i), out);
109  EXPECT_EQ(out.frame_id_, i);
110  EXPECT_EQ(out.stamp_, ros::Time().fromNSec(i));
111  }
112 
113 }
114 
115 TEST(TimeCache, RepeatabilityRandomInsertOrder)
116 {
117  seed_rand();
118 
119  tf::TimeCache cache;
120  double my_vals[] = {13,2,5,4,9,7,3,11,15,14,12,1,6,10,0,8};
121  std::vector<double> values (my_vals, my_vals + sizeof(my_vals)/sizeof(double));
122  unsigned int runs = values.size();
123 
125  t.setIdentity();
126 
127  for ( uint64_t i = 0; i <runs ; i++ )
128  {
129  values[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
130  t.stamp_ = ros::Time().fromNSec(i);
131 
132  TransformStorage stor(t, i, 0);
133 
134  cache.insertData(stor);
135  }
136 
137  TransformStorage out;
138  for ( uint64_t i = 1; i < runs ; i++ )
139  {
140  cache.getData(ros::Time().fromNSec(i), out);
141  EXPECT_EQ(out.frame_id_, i);
142  EXPECT_EQ(out.stamp_, ros::Time().fromNSec(i));
143  }
144 }
145 
146 TEST(TimeCache, ZeroAtFront)
147 {
148  uint64_t runs = 100;
149 
150  seed_rand();
151 
152  tf::TimeCache cache;
153  std::vector<double> values(runs);
154 
156  t.setIdentity();
157 
158  for ( uint64_t i = 0; i <runs ; i++ )
159  {
160  values[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
161  t.stamp_ = ros::Time().fromNSec(i);
162 
163  TransformStorage stor(t, i, 0);
164 
165  cache.insertData(stor);
166  }
167 
168  t.stamp_ = ros::Time().fromNSec(runs);
169  TransformStorage stor(t, runs, 0);
170  cache.insertData(stor);
171 
172  for ( uint64_t i = 1; i < runs ; i++ )
173  {
174  cache.getData(ros::Time().fromNSec(i), stor);
175  EXPECT_EQ(stor.frame_id_, i);
176  EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(i));
177  }
178 
179  cache.getData(ros::Time(), stor);
180  EXPECT_EQ(stor.frame_id_, runs);
181  EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(runs));
182 
183 
184  t.stamp_ = ros::Time().fromNSec(runs+1);
185  TransformStorage stor2(t, runs+1, 0);
186  cache.insertData(stor2);
187 
188  //Make sure we get a different value now that a new values is added at the front
189  cache.getData(ros::Time(), stor);
190  EXPECT_EQ(stor.frame_id_, runs+1);
191  EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(runs+1));
192 }
193 
194 TEST(TimeCache, CartesianInterpolation)
195 {
196  uint64_t runs = 100;
197  double epsilon = 1e-6;
198  seed_rand();
199 
200  tf::TimeCache cache;
201  std::vector<double> xvalues(2);
202  std::vector<double> yvalues(2);
203  std::vector<double> zvalues(2);
204 
205  uint64_t offset = 200;
206 
208  t.setIdentity();
209 
210  for ( uint64_t i = 1; i < runs ; i++ )
211  {
212  for (uint64_t step = 0; step < 2 ; step++)
213  {
214  xvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
215  yvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
216  zvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
217 
218  t.setOrigin(tf::Vector3(xvalues[step], yvalues[step], zvalues[step]));
219  t.stamp_ = ros::Time().fromNSec(step * 100 + offset);
220  TransformStorage stor(t, 2, 0);
221  cache.insertData(stor);
222  }
223 
224  TransformStorage out;
225  for (int pos = 0; pos < 100 ; pos++)
226  {
227  cache.getData(ros::Time().fromNSec(offset + pos), out);
228  double x_out = out.translation_.x();
229  double y_out = out.translation_.y();
230  double z_out = out.translation_.z();
231  EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon);
232  EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon);
233  EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon);
234  }
235 
236 
237  cache.clearList();
238  }
239 }
240 
241 
242 /* TEST IS BROKEN, NEED TO PREVENT THIS
244 TEST(TimeCache, ReparentingInterpolationProtection)
245 {
246  double epsilon = 1e-6;
247  uint64_t offset = 555;
248 
249  tf::TimeCache cache;
250  std::vector<double> xvalues(2);
251  std::vector<double> yvalues(2);
252  std::vector<double> zvalues(2);
253 
254  StampedTransform t;
255  t.setIdentity();
256 
257  for (uint64_t step = 0; step < 2 ; step++)
258  {
259  xvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
260  yvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
261  zvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
262 
263  t.setOrigin(tf::Vector3(xvalues[step], yvalues[step], zvalues[step]));
264  t.stamp_ = ros::Time().fromNSec(step * 100 + offset);
265  TransformStorage stor(t, step + 4, 0);
266  cache.insertData(stor);
267  }
268 
269  TransformStorage out;
270  for (int pos = 0; pos < 100 ; pos ++)
271  {
272  EXPECT_TRUE(cache.getData(ros::Time().fromNSec(offset + pos), out));
273  double x_out = out.translation_.x();
274  double y_out = out.translation_.y();
275  double z_out = out.translation_.z();
276  EXPECT_NEAR(xvalues[0], x_out, epsilon);
277  EXPECT_NEAR(yvalues[0], y_out, epsilon);
278  EXPECT_NEAR(zvalues[0], z_out, epsilon);
279  }
280 
281  for (int pos = 100; pos < 120 ; pos ++)
282  {
283  EXPECT_TRUE(cache.getData(ros::Time().fromNSec(offset + pos), out));
284  double x_out = out.translation_.x();
285  double y_out = out.translation_.y();
286  double z_out = out.translation_.z();
287  EXPECT_NEAR(xvalues[1], x_out, epsilon);
288  EXPECT_NEAR(yvalues[1], y_out, epsilon);
289  EXPECT_NEAR(zvalues[1], z_out, epsilon);
290  }
291 }
292 
293 // EXTRAPOLATION DISABLED
294 TEST(TimeCache, CartesianExtrapolation)
295 {
296  uint64_t runs = 100;
297  double epsilon = 1e-5;
298  seed_rand();
299 
300  tf::TimeCache cache;
301  std::vector<double> xvalues(2);
302  std::vector<double> yvalues(2);
303  std::vector<double> zvalues(2);
304 
305  uint64_t offset = 555;
306 
307  StampedTransform t;
308  t.setIdentity();
309 
310  for ( uint64_t i = 1; i < runs ; i++ )
311  {
312  for (uint64_t step = 0; step < 2 ; step++)
313  {
314  xvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
315  yvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
316  zvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
317 
318  t.setOrigin(tf::Vector3(xvalues[step], yvalues[step], zvalues[step]));
319  t.stamp_ = ros::Time().fromNSec(step * 100 + offset);
320  TransformStorage stor(t, 2, 0);
321  cache.insertData(stor);
322  }
323 
324  TransformStorage out;
325  for (int pos = -200; pos < 300 ; pos ++)
326  {
327  cache.getData(ros::Time().fromNSec(offset + pos), out);
328  double x_out = out.translation_.x();
329  double y_out = out.translation_.y();
330  double z_out = out.translation_.z();
331  EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon);
332  EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon);
333  EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon);
334  }
335 
336  cache.clearList();
337  }
338 }
339 */
340 
341 TEST(Bullet, Slerp)
342 {
343  uint64_t runs = 100;
344  seed_rand();
345 
346  tf::Quaternion q1, q2;
347  q1.setEuler(0,0,0);
348 
349  for (uint64_t i = 0 ; i < runs ; i++)
350  {
351  q2.setEuler(1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX,
352  1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX,
353  1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX);
354 
355 
356  tf::Quaternion q3 = slerp(q1,q2,0.5);
357 
358  EXPECT_NEAR(q3.angle(q1), q2.angle(q3), 1e-5);
359  }
360 
361 }
362 
363 
364 TEST(TimeCache, AngularInterpolation)
365 {
366  uint64_t runs = 100;
367  double epsilon = 1e-6;
368  seed_rand();
369 
370  tf::TimeCache cache;
371  std::vector<double> yawvalues(2);
372  std::vector<double> pitchvalues(2);
373  std::vector<double> rollvalues(2);
374  uint64_t offset = 200;
375 
376  std::vector<tf::Quaternion> quats(2);
377 
379  t.setIdentity();
380 
381  for ( uint64_t i = 1; i < runs ; i++ )
382  {
383  for (uint64_t step = 0; step < 2 ; step++)
384  {
385  yawvalues[step] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX / 100.0;
386  pitchvalues[step] = 0;//10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
387  rollvalues[step] = 0;//10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
388  quats[step].setRPY(yawvalues[step], pitchvalues[step], rollvalues[step]);
389  t.setRotation(quats[step]);
390  t.stamp_ = ros::Time().fromNSec(offset + (step * 100)); //step = 0 or 1
391  TransformStorage stor(t, 3, 0);
392  cache.insertData(stor);
393  }
394 
395  TransformStorage out;
396  for (int pos = 0; pos < 100 ; pos ++)
397  {
398  cache.getData(ros::Time().fromNSec(offset + pos), out); //get the transform for the position
399  tf::Quaternion quat = out.rotation_; //get the quaternion out of the transform
400 
401  //Generate a ground truth quaternion directly calling slerp
402  tf::Quaternion ground_truth = quats[0].slerp(quats[1], pos/100.0);
403 
404  //Make sure the transformed one and the direct call match
405  EXPECT_NEAR(0, angle(ground_truth, quat), epsilon);
406  }
407 
408  cache.clearList();
409  }
410 }
411 
412 TEST(TimeCache, DuplicateEntries)
413 {
414 
415  TimeCache cache;
416 
418  t.setIdentity();
419  t.stamp_ = ros::Time().fromNSec(1);
420  TransformStorage stor(t, 3, 0);
421  cache.insertData(stor);
422  cache.insertData(stor);
423 
424 
425  cache.getData(ros::Time().fromNSec(1), stor);
426 
427  EXPECT_TRUE(!std::isnan(stor.translation_.x()));
428  EXPECT_TRUE(!std::isnan(stor.translation_.y()));
429  EXPECT_TRUE(!std::isnan(stor.translation_.z()));
430  EXPECT_TRUE(!std::isnan(stor.rotation_.x()));
431  EXPECT_TRUE(!std::isnan(stor.rotation_.y()));
432  EXPECT_TRUE(!std::isnan(stor.rotation_.z()));
433  EXPECT_TRUE(!std::isnan(stor.rotation_.w()));
434 }
435 
436 
437 int main(int argc, char **argv){
438  testing::InitGoogleTest(&argc, argv);
439  return RUN_ALL_TESTS();
440 }
double epsilon
Definition: quaternion.cpp:38
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
Set the rotational element by Quaternion.
Definition: Transform.h:163
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
TEST(TimeCache, Repeatability)
Time & fromNSec(uint64_t t)
std::vector< double > values
CompactFrameID frame_id_
Definition: time_cache.h:86
void clearList()
Definition: cache.cpp:264
tfScalar angle(const Quaternion &q) const
Return the half angle between this quaternion and the other.
Definition: Quaternion.h:213
A class to keep a sorted linked list in time This builds and maintains a list of timestamped data...
Definition: time_cache.h:97
Definition: exceptions.h:38
ros::Time stamp_
The timestamp associated with this transform.
TFSIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
Return the result of spherical linear interpolation betwen two quaternions.
Definition: Quaternion.h:432
tf::Vector3 translation_
Definition: time_cache.h:84
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
Definition: Quaternion.h:407
void setIdentity()
Set this transformation to the identity.
Definition: Transform.h:170
int main(int argc, char **argv)
bool insertData(const TransformStorage &new_data)
Definition: cache.cpp:239
Quaternion slerp(const Quaternion &q, const tfScalar &t) const
Return the quaternion which is the result of Spherical Linear Interpolation between this and the othe...
Definition: Quaternion.h:316
void setEuler(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
Set the quaternion using Euler angles.
Definition: Quaternion.h:76
bool getData(ros::Time time, TransformStorage &data_out, std::string *error_str=0)
Definition: cache.cpp:192
unsigned int step
Storage for transforms and their parent.
Definition: time_cache.h:54
tf::Quaternion rotation_
Definition: time_cache.h:83
void seed_rand()
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
Set the translational element.
Definition: Transform.h:148
std::string frame_id_
The frame_id of the coordinate frame in which this transform is defined.
The Stamped Transform datatype used by tf.


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Feb 28 2022 22:26:19