File: cache_unittest.cpp

package info (click to toggle)
ros-geometry 1.13.2-11
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid, trixie
  • size: 1,272 kB
  • sloc: cpp: 8,457; python: 1,858; xml: 149; sh: 28; makefile: 3
file content (441 lines) | stat: -rw-r--r-- 12,804 bytes parent folder | download | duplicates (3)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
/*
 * Copyright (c) 2008, Willow Garage, Inc.
 * All rights reserved.
 * 
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 * 
 *     * Redistributions of source code must retain the above copyright
 *       notice, this list of conditions and the following disclaimer.
 *     * Redistributions in binary form must reproduce the above copyright
 *       notice, this list of conditions and the following disclaimer in the
 *       documentation and/or other materials provided with the distribution.
 *     * Neither the name of the Willow Garage, Inc. nor the names of its
 *       contributors may be used to endorse or promote products derived from
 *       this software without specific prior written permission.
 * 
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 */

#include <gtest/gtest.h>
#include <tf/tf.h>
#include <sys/time.h>
#include "tf/LinearMath/Vector3.h"
#include "tf/LinearMath/Matrix3x3.h"


void seed_rand()
{
  //Seed random number generator with current microseond count
  timeval temp_time_struct;
  gettimeofday(&temp_time_struct,NULL);
  srand(temp_time_struct.tv_usec);
}

using namespace tf;


TEST(TimeCache, Repeatability)
{
  unsigned int runs = 100;

  seed_rand();
  
  tf::TimeCache  cache;
  std::vector<double> values(runs);

  StampedTransform t;
  t.setIdentity();
  
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    values[i] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    std::stringstream ss;
    ss << values[i];
    t.frame_id_ = ss.str();
    t.stamp_ = ros::Time().fromNSec(i);
    
    TransformStorage stor(t, i, 0);

    cache.insertData(stor);
  }

  TransformStorage out;
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    cache.getData(ros::Time().fromNSec(i), out);
    EXPECT_EQ(out.frame_id_, i);
    EXPECT_EQ(out.stamp_, ros::Time().fromNSec(i));
  }
  
}


TEST(TimeCache, RepeatabilityReverseInsertOrder)
{
  unsigned int runs = 100;

  seed_rand();
  
  tf::TimeCache  cache;
  std::vector<double> values(runs);

  StampedTransform t;
  t.setIdentity();
  
  for ( int i = runs -1; i >= 0 ; i-- )
  {
    values[i] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    t.stamp_ = ros::Time().fromNSec(i);

    TransformStorage stor(t, i, 0);

    cache.insertData(stor);
  }

  TransformStorage out;
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    cache.getData(ros::Time().fromNSec(i), out);
    EXPECT_EQ(out.frame_id_, i);
    EXPECT_EQ(out.stamp_, ros::Time().fromNSec(i));
  }
  
}

TEST(TimeCache, RepeatabilityRandomInsertOrder)
{
  seed_rand();
  
  tf::TimeCache  cache;
  double my_vals[] = {13,2,5,4,9,7,3,11,15,14,12,1,6,10,0,8};
  std::vector<double> values (my_vals, my_vals + sizeof(my_vals)/sizeof(double)); 
  unsigned int runs = values.size();

  StampedTransform t;
  t.setIdentity();

  for ( uint64_t i = 0; i <runs ; i++ )
  {
    values[i] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    t.stamp_ = ros::Time().fromNSec(i);

    TransformStorage stor(t, i, 0);
    
    cache.insertData(stor);
  }

  TransformStorage out;
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    cache.getData(ros::Time().fromNSec(i), out);
    EXPECT_EQ(out.frame_id_, i);
    EXPECT_EQ(out.stamp_, ros::Time().fromNSec(i));
  }
}

TEST(TimeCache, ZeroAtFront)
{
  uint64_t runs = 100;

  seed_rand();
  
  tf::TimeCache  cache;
  std::vector<double> values(runs);

  StampedTransform t;
  t.setIdentity();
  
  for ( uint64_t i = 0; i <runs ; i++ )
  {
    values[i] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    t.stamp_ = ros::Time().fromNSec(i);

    TransformStorage stor(t, i, 0);
    
    cache.insertData(stor);
  }

  t.stamp_ = ros::Time().fromNSec(runs);
  TransformStorage stor(t, runs, 0);
  cache.insertData(stor);
  
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    cache.getData(ros::Time().fromNSec(i), stor);
    EXPECT_EQ(stor.frame_id_, i);
    EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(i));
  }

  cache.getData(ros::Time(), stor);
  EXPECT_EQ(stor.frame_id_, runs);
  EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(runs));


  t.stamp_ = ros::Time().fromNSec(runs+1);
  TransformStorage stor2(t, runs+1, 0);
  cache.insertData(stor2);

  //Make sure we get a different value now that a new values is added at the front
  cache.getData(ros::Time(), stor);
  EXPECT_EQ(stor.frame_id_, runs+1);
  EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(runs+1));
}

TEST(TimeCache, CartesianInterpolation)
{
  uint64_t runs = 100;
  double epsilon = 1e-6;
  seed_rand();
  
  tf::TimeCache  cache;
  std::vector<double> xvalues(2);
  std::vector<double> yvalues(2);
  std::vector<double> zvalues(2);

  uint64_t offset = 200;

  StampedTransform t;
  t.setIdentity();
  
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    for (uint64_t step = 0; step < 2 ; step++)
    {
      xvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
      yvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
      zvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    
      t.setOrigin(tf::Vector3(xvalues[step], yvalues[step], zvalues[step]));
      t.stamp_ = ros::Time().fromNSec(step * 100 + offset);
      TransformStorage stor(t, 2, 0);
      cache.insertData(stor);
    }
    
    TransformStorage out;
    for (int pos = 0; pos < 100 ; pos++)
    {
      cache.getData(ros::Time().fromNSec(offset + pos), out);
      double x_out = out.translation_.x();
      double y_out = out.translation_.y();
      double z_out = out.translation_.z();
      EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon);
      EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon);
      EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon);
    }
    

    cache.clearList();
  }
}


/* TEST IS BROKEN, NEED TO PREVENT THIS
///\brief Make sure we dont' interpolate across reparented data
TEST(TimeCache, ReparentingInterpolationProtection)
{
  double epsilon = 1e-6;
  uint64_t offset = 555;

  tf::TimeCache cache;
  std::vector<double> xvalues(2);
  std::vector<double> yvalues(2);
  std::vector<double> zvalues(2);

  StampedTransform t;
  t.setIdentity();

  for (uint64_t step = 0; step < 2 ; step++)
  {
    xvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    yvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    zvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    
    t.setOrigin(tf::Vector3(xvalues[step], yvalues[step], zvalues[step]));
    t.stamp_ = ros::Time().fromNSec(step * 100 + offset);
    TransformStorage stor(t, step + 4, 0);
    cache.insertData(stor);
  }
  
  TransformStorage out;
  for (int pos = 0; pos < 100 ; pos ++)
  {
    EXPECT_TRUE(cache.getData(ros::Time().fromNSec(offset + pos), out));
    double x_out = out.translation_.x();
    double y_out = out.translation_.y();
    double z_out = out.translation_.z();
    EXPECT_NEAR(xvalues[0], x_out, epsilon);
    EXPECT_NEAR(yvalues[0], y_out, epsilon);
    EXPECT_NEAR(zvalues[0], z_out, epsilon);
  }
  
  for (int pos = 100; pos < 120 ; pos ++)
  {
    EXPECT_TRUE(cache.getData(ros::Time().fromNSec(offset + pos), out));
    double x_out = out.translation_.x();
    double y_out = out.translation_.y();
    double z_out = out.translation_.z();
    EXPECT_NEAR(xvalues[1], x_out, epsilon);
    EXPECT_NEAR(yvalues[1], y_out, epsilon);
    EXPECT_NEAR(zvalues[1], z_out, epsilon);
  }
}

// EXTRAPOLATION DISABLED
TEST(TimeCache, CartesianExtrapolation)
{
  uint64_t runs = 100;
  double epsilon = 1e-5;
  seed_rand();
  
  tf::TimeCache  cache;
  std::vector<double> xvalues(2);
  std::vector<double> yvalues(2);
  std::vector<double> zvalues(2);

  uint64_t offset = 555;

  StampedTransform t;
  t.setIdentity();
  
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    for (uint64_t step = 0; step < 2 ; step++)
    {
      xvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
      yvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
      zvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
    
      t.setOrigin(tf::Vector3(xvalues[step], yvalues[step], zvalues[step]));
      t.stamp_ = ros::Time().fromNSec(step * 100 + offset);
      TransformStorage stor(t, 2, 0);
      cache.insertData(stor);
    }
    
    TransformStorage out;
    for (int pos = -200; pos < 300 ; pos ++)
    {
      cache.getData(ros::Time().fromNSec(offset + pos), out);
      double x_out = out.translation_.x();
      double y_out = out.translation_.y();
      double z_out = out.translation_.z();
      EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon);
      EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon);
      EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon);
    }
    
    cache.clearList();
  }
}
*/

TEST(Bullet, Slerp)
{
  uint64_t runs = 100;
  seed_rand();

  tf::Quaternion q1, q2;
  q1.setEuler(0,0,0);
  
  for (uint64_t i = 0 ; i < runs ; i++)
  {
    q2.setEuler(1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX,
                1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX,
                1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX);
    
    
    tf::Quaternion q3 = slerp(q1,q2,0.5);
    
    EXPECT_NEAR(q3.angle(q1), q2.angle(q3), 1e-5);
  }

}


TEST(TimeCache, AngularInterpolation)
{
  uint64_t runs = 100;
  double epsilon = 1e-6;
  seed_rand();
  
  tf::TimeCache  cache;
  std::vector<double> yawvalues(2);
  std::vector<double> pitchvalues(2);
  std::vector<double> rollvalues(2);
  uint64_t offset = 200;

  std::vector<tf::Quaternion> quats(2);

  StampedTransform t;
  t.setIdentity();
  
  for ( uint64_t i = 1; i < runs ; i++ )
  {
    for (uint64_t step = 0; step < 2 ; step++)
    {
      yawvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX / 100.0;
      pitchvalues[step] = 0;//10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
      rollvalues[step] = 0;//10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
      quats[step].setRPY(yawvalues[step], pitchvalues[step], rollvalues[step]);
      t.setRotation(quats[step]);
      t.stamp_ = ros::Time().fromNSec(offset + (step * 100)); //step = 0 or 1
      TransformStorage stor(t, 3, 0);
      cache.insertData(stor);
    }
    
    TransformStorage out;
    for (int pos = 0; pos < 100 ; pos ++)
    {
      cache.getData(ros::Time().fromNSec(offset + pos), out); //get the transform for the position
      tf::Quaternion quat = out.rotation_; //get the quaternion out of the transform

      //Generate a ground truth quaternion directly calling slerp
      tf::Quaternion ground_truth = quats[0].slerp(quats[1], pos/100.0);
      
      //Make sure the transformed one and the direct call match
      EXPECT_NEAR(0, angle(ground_truth, quat), epsilon);
    }
    
    cache.clearList();
  }
}

TEST(TimeCache, DuplicateEntries)
{

  TimeCache cache;

  StampedTransform t;
  t.setIdentity();
  t.stamp_ = ros::Time().fromNSec(1);
  TransformStorage stor(t, 3, 0);
  cache.insertData(stor);
  cache.insertData(stor);


  cache.getData(ros::Time().fromNSec(1), stor);
  
  EXPECT_TRUE(!std::isnan(stor.translation_.x()));
  EXPECT_TRUE(!std::isnan(stor.translation_.y()));
  EXPECT_TRUE(!std::isnan(stor.translation_.z()));
  EXPECT_TRUE(!std::isnan(stor.rotation_.x()));
  EXPECT_TRUE(!std::isnan(stor.rotation_.y()));
  EXPECT_TRUE(!std::isnan(stor.rotation_.z()));
  EXPECT_TRUE(!std::isnan(stor.rotation_.w()));
}


int main(int argc, char **argv){
  testing::InitGoogleTest(&argc, argv);
  return RUN_ALL_TESTS();
}