$search
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 00030 #include <gtest/gtest.h> 00031 #include <tf2/time_cache.h> 00032 #include <sys/time.h> 00033 #include "LinearMath/btVector3.h" 00034 #include "LinearMath/btMatrix3x3.h" 00035 #include <stdexcept> 00036 00037 #include <geometry_msgs/TransformStamped.h> 00038 00039 #include <cmath> 00040 00041 std::vector<double> values; 00042 unsigned int step = 0; 00043 00044 void seed_rand() 00045 { 00046 values.clear(); 00047 for (unsigned int i = 0; i < 1000; i++) 00048 { 00049 int pseudo_rand = std::floor(i * M_PI); 00050 values.push_back(( pseudo_rand % 100)/50.0 - 1.0); 00051 //printf("Seeding with %f\n", values.back()); 00052 } 00053 }; 00054 00055 00056 double get_rand() 00057 { 00058 if (values.size() == 0) throw std::runtime_error("you need to call seed_rand first"); 00059 if (step >= values.size()) 00060 step = 0; 00061 else 00062 step++; 00063 return values[step]; 00064 } 00065 00066 using namespace tf2; 00067 00068 00069 void setIdentity(TransformStorage& stor) 00070 { 00071 stor.translation_.setValue(0.0, 0.0, 0.0); 00072 stor.rotation_.setValue(0.0, 0.0, 0.0, 1.0); 00073 } 00074 00075 TEST(TimeCache, Repeatability) 00076 { 00077 unsigned int runs = 100; 00078 00079 tf2::TimeCache cache; 00080 00081 TransformStorage stor; 00082 setIdentity(stor); 00083 00084 for ( uint64_t i = 1; i < runs ; i++ ) 00085 { 00086 stor.frame_id_ = i; 00087 stor.stamp_ = ros::Time().fromNSec(i); 00088 00089 cache.insertData(stor); 00090 } 00091 00092 for ( uint64_t i = 1; i < runs ; i++ ) 00093 00094 { 00095 cache.getData(ros::Time().fromNSec(i), stor); 00096 EXPECT_EQ(stor.frame_id_, i); 00097 EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(i)); 00098 } 00099 00100 } 00101 00102 TEST(TimeCache, RepeatabilityReverseInsertOrder) 00103 { 00104 unsigned int runs = 100; 00105 00106 tf2::TimeCache cache; 00107 00108 TransformStorage stor; 00109 setIdentity(stor); 00110 00111 for ( int i = runs -1; i >= 0 ; i-- ) 00112 { 00113 stor.frame_id_ = i; 00114 stor.stamp_ = ros::Time().fromNSec(i); 00115 00116 cache.insertData(stor); 00117 } 00118 for ( uint64_t i = 1; i < runs ; i++ ) 00119 00120 { 00121 cache.getData(ros::Time().fromNSec(i), stor); 00122 EXPECT_EQ(stor.frame_id_, i); 00123 EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(i)); 00124 } 00125 00126 } 00127 00128 #if 0 // jfaust: this doesn't seem to actually be testing random insertion? 00129 TEST(TimeCache, RepeatabilityRandomInsertOrder) 00130 { 00131 00132 seed_rand(); 00133 00134 tf2::TimeCache cache; 00135 double my_vals[] = {13,2,5,4,9,7,3,11,15,14,12,1,6,10,0,8}; 00136 std::vector<double> values (my_vals, my_vals + sizeof(my_vals)/sizeof(double)); 00137 unsigned int runs = values.size(); 00138 00139 TransformStorage stor; 00140 setIdentity(stor); 00141 for ( uint64_t i = 0; i <runs ; i++ ) 00142 { 00143 values[i] = 10.0 * get_rand(); 00144 std::stringstream ss; 00145 ss << values[i]; 00146 stor.header.frame_id = ss.str(); 00147 stor.frame_id_ = i; 00148 stor.stamp_ = ros::Time().fromNSec(i); 00149 00150 cache.insertData(stor); 00151 } 00152 for ( uint64_t i = 1; i < runs ; i++ ) 00153 00154 { 00155 cache.getData(ros::Time().fromNSec(i), stor); 00156 EXPECT_EQ(stor.frame_id_, i); 00157 EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(i)); 00158 std::stringstream ss; 00159 ss << values[i]; 00160 EXPECT_EQ(stor.header.frame_id, ss.str()); 00161 } 00162 00163 } 00164 #endif 00165 00166 TEST(TimeCache, ZeroAtFront) 00167 { 00168 uint64_t runs = 100; 00169 00170 tf2::TimeCache cache; 00171 00172 TransformStorage stor; 00173 setIdentity(stor); 00174 00175 for ( uint64_t i = 1; i < runs ; i++ ) 00176 { 00177 stor.frame_id_ = i; 00178 stor.stamp_ = ros::Time().fromNSec(i); 00179 00180 cache.insertData(stor); 00181 } 00182 00183 stor.frame_id_ = runs; 00184 stor.stamp_ = ros::Time().fromNSec(runs); 00185 cache.insertData(stor); 00186 00187 for ( uint64_t i = 1; i < runs ; i++ ) 00188 00189 { 00190 cache.getData(ros::Time().fromNSec(i), stor); 00191 EXPECT_EQ(stor.frame_id_, i); 00192 EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(i)); 00193 } 00194 00195 cache.getData(ros::Time(), stor); 00196 EXPECT_EQ(stor.frame_id_, runs); 00197 EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(runs)); 00198 00199 stor.frame_id_ = runs; 00200 stor.stamp_ = ros::Time().fromNSec(runs+1); 00201 cache.insertData(stor); 00202 00203 00204 //Make sure we get a different value now that a new values is added at the front 00205 cache.getData(ros::Time(), stor); 00206 EXPECT_EQ(stor.frame_id_, runs); 00207 EXPECT_EQ(stor.stamp_, ros::Time().fromNSec(runs+1)); 00208 00209 } 00210 00211 TEST(TimeCache, CartesianInterpolation) 00212 { 00213 uint64_t runs = 100; 00214 double epsilon = 2e-6; 00215 seed_rand(); 00216 00217 tf2::TimeCache cache; 00218 std::vector<double> xvalues(2); 00219 std::vector<double> yvalues(2); 00220 std::vector<double> zvalues(2); 00221 00222 uint64_t offset = 200; 00223 00224 TransformStorage stor; 00225 setIdentity(stor); 00226 00227 for ( uint64_t i = 1; i < runs ; i++ ) 00228 { 00229 00230 for (uint64_t step = 0; step < 2 ; step++) 00231 { 00232 xvalues[step] = 10.0 * get_rand(); 00233 yvalues[step] = 10.0 * get_rand(); 00234 zvalues[step] = 10.0 * get_rand(); 00235 00236 stor.translation_.setValue(xvalues[step], yvalues[step], zvalues[step]); 00237 stor.frame_id_ = 2; 00238 stor.stamp_ = ros::Time().fromNSec(step * 100 + offset); 00239 cache.insertData(stor); 00240 } 00241 00242 for (int pos = 0; pos < 100 ; pos ++) 00243 { 00244 cache.getData(ros::Time().fromNSec(offset + pos), stor); 00245 double x_out = stor.translation_.x(); 00246 double y_out = stor.translation_.y(); 00247 double z_out = stor.translation_.z(); 00248 // printf("pose %d, %f %f %f, expected %f %f %f\n", pos, x_out, y_out, z_out, 00249 // xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100., 00250 // yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, 00251 // zvalues[0] + (xvalues[1] - zvalues[0]) * (double)pos/100.0); 00252 EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon); 00253 EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon); 00254 EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon); 00255 } 00256 00257 00258 cache.clearList(); 00259 } 00260 00261 00262 } 00263 00265 TEST(TimeCache, ReparentingInterpolationProtection) 00266 { 00267 double epsilon = 1e-6; 00268 uint64_t offset = 555; 00269 00270 seed_rand(); 00271 00272 tf2::TimeCache cache; 00273 std::vector<double> xvalues(2); 00274 std::vector<double> yvalues(2); 00275 std::vector<double> zvalues(2); 00276 00277 TransformStorage stor; 00278 setIdentity(stor); 00279 00280 for (uint64_t step = 0; step < 2 ; step++) 00281 { 00282 xvalues[step] = 10.0 * get_rand(); 00283 yvalues[step] = 10.0 * get_rand(); 00284 zvalues[step] = 10.0 * get_rand(); 00285 00286 stor.translation_.setValue(xvalues[step], yvalues[step], zvalues[step]); 00287 stor.frame_id_ = step + 4; 00288 stor.stamp_ = ros::Time().fromNSec(step * 100 + offset); 00289 cache.insertData(stor); 00290 } 00291 00292 for (int pos = 0; pos < 100 ; pos ++) 00293 { 00294 EXPECT_TRUE(cache.getData(ros::Time().fromNSec(offset + pos), stor)); 00295 double x_out = stor.translation_.x(); 00296 double y_out = stor.translation_.y(); 00297 double z_out = stor.translation_.z(); 00298 EXPECT_NEAR(xvalues[0], x_out, epsilon); 00299 EXPECT_NEAR(yvalues[0], y_out, epsilon); 00300 EXPECT_NEAR(zvalues[0], z_out, epsilon); 00301 } 00302 } 00303 00304 TEST(Bullet, Slerp) 00305 { 00306 00307 uint64_t runs = 100; 00308 seed_rand(); 00309 00310 btQuaternion q1, q2; 00311 q1.setEuler(0,0,0); 00312 00313 for (uint64_t i = 0 ; i < runs ; i++) 00314 { 00315 q2.setEuler(1.0 * get_rand(), 00316 1.0 * get_rand(), 00317 1.0 * get_rand()); 00318 00319 00320 btQuaternion q3 = slerp(q1,q2,0.5); 00321 00322 EXPECT_NEAR(q3.angle(q1), q2.angle(q3), 1e-5); 00323 } 00324 00325 } 00326 00327 00328 TEST(TimeCache, AngularInterpolation) 00329 { 00330 uint64_t runs = 100; 00331 double epsilon = 1e-6; 00332 seed_rand(); 00333 00334 tf2::TimeCache cache; 00335 std::vector<double> yawvalues(2); 00336 std::vector<double> pitchvalues(2); 00337 std::vector<double> rollvalues(2); 00338 uint64_t offset = 200; 00339 00340 std::vector<btQuaternion> quats(2); 00341 00342 TransformStorage stor; 00343 setIdentity(stor); 00344 00345 for ( uint64_t i = 1; i < runs ; i++ ) 00346 { 00347 00348 for (uint64_t step = 0; step < 2 ; step++) 00349 { 00350 yawvalues[step] = 10.0 * get_rand() / 100.0; 00351 pitchvalues[step] = 0;//10.0 * get_rand(); 00352 rollvalues[step] = 0;//10.0 * get_rand(); 00353 quats[step].setRPY(yawvalues[step], pitchvalues[step], rollvalues[step]); 00354 stor.rotation_ = quats[step]; 00355 stor.frame_id_ = 3; 00356 stor.stamp_ = ros::Time().fromNSec(offset + (step * 100)); //step = 0 or 1 00357 cache.insertData(stor); 00358 } 00359 00360 for (int pos = 0; pos < 100 ; pos ++) 00361 { 00362 EXPECT_TRUE(cache.getData(ros::Time().fromNSec(offset + pos), stor)); //get the transform for the position 00363 btQuaternion quat (stor.rotation_); 00364 00365 //Generate a ground truth quaternion directly calling slerp 00366 btQuaternion ground_truth = quats[0].slerp(quats[1], pos/100.0); 00367 00368 //Make sure the transformed one and the direct call match 00369 EXPECT_NEAR(0, angle(ground_truth, quat), epsilon); 00370 00371 } 00372 00373 cache.clearList(); 00374 } 00375 00376 00377 } 00378 00379 TEST(TimeCache, DuplicateEntries) 00380 { 00381 00382 TimeCache cache; 00383 00384 TransformStorage stor; 00385 setIdentity(stor); 00386 stor.frame_id_ = 3; 00387 stor.stamp_ = ros::Time().fromNSec(1); 00388 00389 cache.insertData(stor); 00390 00391 cache.insertData(stor); 00392 00393 00394 cache.getData(ros::Time().fromNSec(1), stor); 00395 00396 //printf(" stor is %f\n", stor.translation_.x()); 00397 EXPECT_TRUE(!std::isnan(stor.translation_.x())); 00398 EXPECT_TRUE(!std::isnan(stor.translation_.y())); 00399 EXPECT_TRUE(!std::isnan(stor.translation_.z())); 00400 EXPECT_TRUE(!std::isnan(stor.rotation_.x())); 00401 EXPECT_TRUE(!std::isnan(stor.rotation_.y())); 00402 EXPECT_TRUE(!std::isnan(stor.rotation_.z())); 00403 EXPECT_TRUE(!std::isnan(stor.rotation_.w())); 00404 } 00405 00406 int main(int argc, char **argv){ 00407 testing::InitGoogleTest(&argc, argv); 00408 return RUN_ALL_TESTS(); 00409 }