tf_benchmark.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 
35 #include "tf/LinearMath/Vector3.h"
36 
37 void seed_rand()
38 {
39  //Seed random number generator with current microseond count
40  std::srand(std::time(0));
41 };
42 
43 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
44 {
45  seed_rand();
46  for ( uint64_t i = 0; i < runs ; i++ )
47  {
48  xvalues[i] = 1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
49  yvalues[i] = 1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
50  zvalues[i] = 1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
51  }
52 }
53 
54 
55 using namespace tf;
56 
57 
58 TEST(tf_benchmark, canTransformCacheLength0)
59 {
60  tf::Transformer mTR(true);
61 
62  uint64_t runs = 100000;
63  ros::WallTime start_time = ros::WallTime::now();
64 
65 
66  start_time = ros::WallTime::now();
67  for (uint64_t i = 0 ; i < runs; i++)
68  {
69  EXPECT_FALSE(mTR.canTransform("target","source_frame", ros::Time::now()));
70  }
71  ros::WallDuration run_duration = ros::WallTime::now() - start_time;
72  double frequency = (double)runs / run_duration.toSec() ;
73  printf("can frequency %.2f KHz\n", frequency / 1000.0);
74  EXPECT_GT( frequency, 10000.0);
75 }
76 
77 
78 TEST(tf_benchmark, canTransformCacheLength10000)
79 {
80  tf::Transformer mTR(true);
81 
82  unsigned int cache_length = 10000;
83  for (unsigned int i = 0; i < cache_length; i++)
84  {
85  StampedTransform tranStamped(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(0,0,0)), ros::Time().fromNSec(10.0+i), "my_parent", "child");
86  mTR.setTransform(tranStamped);
87  }
88 
89  uint64_t runs = 100000;
90  ros::WallTime start_time = ros::WallTime::now();
91 
92 
93  //Worst case
94  start_time = ros::WallTime::now();
95  for (uint64_t i = 0 ; i < runs; i++)
96  {
97  EXPECT_TRUE(mTR.canTransform("child","my_parent", ros::Time().fromNSec(10)));
98  }
99  ros::WallDuration run_duration = ros::WallTime::now() - start_time;
100  double frequency = (double)runs / run_duration.toSec() ;
101  printf("Worst Case Frequency %.2f KHz\n", frequency / 1000.0);
102  EXPECT_GT( frequency, 10000.0);
103 
104  //Worst case
105  start_time = ros::WallTime::now();
106  for (uint64_t i = 0 ; i < runs; i++)
107  {
108  EXPECT_TRUE(mTR.canTransform("child","my_parent", ros::Time().fromNSec(10+cache_length/2)));
109  }
110  run_duration = ros::WallTime::now() - start_time;
111  frequency = (double)runs / run_duration.toSec() ;
112  printf("Intermediate Case Frequency %.2f KHz\n", frequency / 1000.0);
113  EXPECT_GT( frequency, 10000.0);
114 
115  //Best case
116  start_time = ros::WallTime::now();
117  for (uint64_t i = 0 ; i < runs; i++)
118  {
119  EXPECT_TRUE(mTR.canTransform("child","my_parent", ros::Time().fromNSec(10+cache_length -1)));
120  }
121  run_duration = ros::WallTime::now() - start_time;
122  frequency = (double)runs / run_duration.toSec() ;
123  printf("Best Case Frequency %.2f KHz\n", frequency / 1000.0);
124  EXPECT_GT( frequency, 10000.0);
125 }
126 
127 TEST(tf_benchmark, lookupTransformCacheLength10000)
128 {
129  tf::Transformer mTR(true);
130 
131  unsigned int cache_length = 10000;
132  for (unsigned int i = 0; i < cache_length; i++)
133  {
134  StampedTransform tranStamped(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(0,0,0)), ros::Time().fromNSec(10.0+i), "my_parent", "child");
135  mTR.setTransform(tranStamped);
136  }
137 
138  uint64_t runs = 100000;
139  ros::WallTime start_time = ros::WallTime::now();
140 
141  StampedTransform rv;
142  //Worst case
143  start_time = ros::WallTime::now();
144  for (uint64_t i = 0 ; i < runs; i++)
145  {
146  mTR.lookupTransform("child","my_parent", ros::Time().fromNSec(10), rv);
147  }
148  ros::WallDuration run_duration = ros::WallTime::now() - start_time;
149  double frequency = (double)runs / run_duration.toSec() ;
150  printf("Worst Case Lookup Frequency %.2f KHz\n", frequency / 1000.0);
151  EXPECT_GT( frequency, 10000.0);
152 
153  //Worst case
154  start_time = ros::WallTime::now();
155  for (uint64_t i = 0 ; i < runs; i++)
156  {
157  mTR.lookupTransform("child","my_parent", ros::Time().fromNSec(10+cache_length/2), rv);
158  }
159  run_duration = ros::WallTime::now() - start_time;
160  frequency = (double)runs / run_duration.toSec() ;
161  printf("Intermediate Case Lookup Frequency %.2f KHz\n", frequency / 1000.0);
162  EXPECT_GT( frequency, 10000.0);
163 
164  //Best case
165  start_time = ros::WallTime::now();
166  for (uint64_t i = 0 ; i < runs; i++)
167  {
168  mTR.lookupTransform("child","my_parent", ros::Time().fromNSec(10+cache_length -1), rv);
169  }
170  run_duration = ros::WallTime::now() - start_time;
171  frequency = (double)runs / run_duration.toSec() ;
172  printf("Best Case Lookup Frequency %.2f KHz\n", frequency / 1000.0);
173  EXPECT_GT( frequency, 10000.0);
174 }
175 
176 TEST(tf_benchmark, benchmarkExhaustiveSearch)
177 {
178  uint64_t runs = 40000;
179  double epsilon = 1e-6;
180  seed_rand();
181 
182  tf::Transformer mTR(true);
183  std::vector<double> xvalues(runs), yvalues(runs), zvalues(runs);
184  for ( uint64_t i = 0; i < runs ; i++ )
185  {
186  xvalues[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
187  yvalues[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
188  zvalues[i] = 10.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
189 
190  StampedTransform tranStamped(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(xvalues[i],yvalues[i],zvalues[i])), ros::Time().fromNSec(10.0 + i), "my_parent", "child");
191  mTR.setTransform(tranStamped);
192  }
193 
194  ros::WallTime start_time = ros::WallTime::now();
195  for ( uint64_t i = 0; i < runs ; i++ )
196 
197  {
198  Stamped<tf::Transform> inpose (tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(0,0,0)), ros::Time().fromNSec(10.0 + i), "child");
199 
200  try{
201  Stamped<Pose> outpose;
202  outpose.setIdentity(); //to make sure things are getting mutated
203  mTR.transformPose("my_parent",inpose, outpose);
204  EXPECT_NEAR(outpose.getOrigin().x(), xvalues[i], epsilon);
205  EXPECT_NEAR(outpose.getOrigin().y(), yvalues[i], epsilon);
206  EXPECT_NEAR(outpose.getOrigin().z(), zvalues[i], epsilon);
207  }
208  catch (tf::TransformException & ex)
209  {
210  std::cout << "TransformExcepion got through!!!!! " << ex.what() << std::endl;
211  bool exception_improperly_thrown = true;
212  EXPECT_FALSE(exception_improperly_thrown);
213  }
214  }
215 
216  Stamped<Pose> inpose (tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(0,0,0)), ros::Time().fromNSec(runs), "child");
217  Stamped<Pose> outpose;
218  outpose.setIdentity(); //to make sure things are getting mutated
219  mTR.transformPose("child",inpose, outpose);
220  EXPECT_NEAR(outpose.getOrigin().x(), 0, epsilon);
221  EXPECT_NEAR(outpose.getOrigin().y(), 0, epsilon);
222  EXPECT_NEAR(outpose.getOrigin().z(), 0, epsilon);
223 
224  ros::WallDuration run_duration = ros::WallTime::now() - start_time;
225  double frequency = (double)runs / run_duration.toSec() ;
226  printf("exhaustive search frequency %.2f KHz\n", frequency / 1000.0);
227  EXPECT_GT( frequency, 500.0);
228 
229 }
230 
231 int main(int argc, char **argv){
232  ros::Time::init();
233  testing::InitGoogleTest(&argc, argv);
234  return RUN_ALL_TESTS();
235 }
double epsilon
Definition: quaternion.cpp:38
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
Test if a transform is possible.
Definition: tf.cpp:357
Time & fromNSec(uint64_t t)
void seed_rand()
int main(int argc, char **argv)
bool setTransform(const StampedTransform &transform, const std::string &authority="default_authority")
Add transform information to the tf data structure.
Definition: tf.cpp:228
Definition: exceptions.h:38
TEST(tf_benchmark, canTransformCacheLength0)
void transformPose(const std::string &target_frame, const Stamped< tf::Pose > &stamped_in, Stamped< tf::Pose > &stamped_out) const
Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as...
Definition: tf.cpp:493
static void init()
The Transform class supports rigid transforms with only translation and rotation and no scaling/shear...
Definition: Transform.h:31
static WallTime now()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
Get the transform between two frames by frame ID.
Definition: tf.cpp:237
void generate_rand_vectors(double scale, uint64_t runs, std::vector< double > &xvalues, std::vector< double > &yvalues, std::vector< double > &zvalues)
static Time now()
The Stamped Transform datatype used by tf.
A Class which provides coordinate transforms between any two frames in a system.
Definition: tf.h:109


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