00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <gtest/gtest.h>
00031 #include <tf2/buffer_core.h>
00032 #include "tf2/exceptions.h"
00033 #include <sys/time.h>
00034 #include <ros/ros.h>
00035 #include "LinearMath/btVector3.h"
00036 #include "LinearMath/btTransform.h"
00037 #include "rostest/permuter.h"
00038
00039 void seed_rand()
00040 {
00041
00042 timeval temp_time_struct;
00043 gettimeofday(&temp_time_struct,NULL);
00044 srand(temp_time_struct.tv_usec);
00045 };
00046
00047 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
00048 {
00049 seed_rand();
00050 for ( uint64_t i = 0; i < runs ; i++ )
00051 {
00052 xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00053 yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00054 zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00055 }
00056 }
00057
00058
00059 void setIdentity(geometry_msgs::Transform& trans)
00060 {
00061 trans.translation.x = 0;
00062 trans.translation.y = 0;
00063 trans.translation.z = 0;
00064 trans.rotation.x = 0;
00065 trans.rotation.y = 0;
00066 trans.rotation.z = 0;
00067 trans.rotation.w = 1;
00068 }
00069
00070
00071 void push_back_i(std::vector<std::string>& children, std::vector<std::string>& parents,
00072 std::vector<double>& dx, std::vector<double>& dy)
00073 {
00074
00075
00076
00077
00078
00079
00080
00081
00082 children.push_back("b");
00083 parents.push_back("a");
00084 dx.push_back(1.0);
00085 dy.push_back(0.0);
00086 children.push_back("c");
00087 parents.push_back("b");
00088 dx.push_back(1.0);
00089 dy.push_back(0.0);
00090 }
00091
00092
00093 void push_back_y(std::vector<std::string>& children, std::vector<std::string>& parents,
00094 std::vector<double>& dx, std::vector<double>& dy)
00095 {
00096
00097
00098
00099
00100
00101
00102
00103
00104 children.push_back("b");
00105 parents.push_back("a");
00106 dx.push_back(1.0);
00107 dy.push_back(0.0);
00108
00109 children.push_back("c");
00110 parents.push_back("b");
00111 dx.push_back(1.0);
00112 dy.push_back(0.0);
00113
00114 children.push_back("d");
00115 parents.push_back("b");
00116 dx.push_back(0.0);
00117 dy.push_back(1.0);
00118
00119 children.push_back("e");
00120 parents.push_back("d");
00121 dx.push_back(0.0);
00122 dy.push_back(1.0);
00123 }
00124
00125 void push_back_v(std::vector<std::string>& children, std::vector<std::string>& parents,
00126 std::vector<double>& dx, std::vector<double>& dy)
00127 {
00128
00129
00130
00131
00132
00133
00134
00135
00136 children.push_back("b");
00137 parents.push_back("a");
00138 dx.push_back(1.0);
00139 dy.push_back(0.0);
00140
00141 children.push_back("c");
00142 parents.push_back("b");
00143 dx.push_back(1.0);
00144 dy.push_back(0.0);
00145
00146 children.push_back("f");
00147 parents.push_back("a");
00148 dx.push_back(0.0);
00149 dy.push_back(1.0);
00150
00151 children.push_back("g");
00152 parents.push_back("f");
00153 dx.push_back(0.0);
00154 dy.push_back(1.0);
00155
00156 }
00157
00158 void push_back_1(std::vector<std::string>& children, std::vector<std::string>& parents,
00159 std::vector<double>& dx, std::vector<double>& dy)
00160 {
00161 children.push_back("2");
00162 parents.push_back("1");
00163 dx.push_back(1.0);
00164 dy.push_back(0.0);
00165 }
00166
00167 void setupTree(tf2::BufferCore& mBC, const std::string& mode, const ros::Time & time, const ros::Duration& interpolation_space = ros::Duration())
00168 {
00169 ROS_DEBUG("Clearing Buffer Core for new test setup");
00170 mBC.clear();
00171
00172 ROS_DEBUG("Setting up test tree for formation %s", mode.c_str());
00173
00174 std::vector<std::string> children;
00175 std::vector<std::string> parents;
00176 std::vector<double> dx, dy;
00177
00178 if (mode == "i")
00179 {
00180 push_back_i(children, parents, dx, dy);
00181 }
00182 else if (mode == "y")
00183 {
00184 push_back_y(children, parents, dx, dy);
00185 }
00186
00187 else if (mode == "v")
00188 {
00189 push_back_v(children, parents, dx, dy);
00190 }
00191
00192 else if (mode == "ring_45")
00193 {
00194
00195
00196 std::vector<std::string> frames;
00197
00198
00199
00200 frames.push_back("a");
00201 frames.push_back("b");
00202 frames.push_back("c");
00203 frames.push_back("d");
00204 frames.push_back("e");
00205 frames.push_back("f");
00206 frames.push_back("g");
00207 frames.push_back("h");
00208 frames.push_back("i");
00209
00210 for (uint8_t iteration = 0; iteration < 2; ++iteration)
00211 {
00212 double direction = 1;
00213 std::string frame_prefix;
00214 if (iteration == 0)
00215 {
00216 frame_prefix = "inverse_";
00217 direction = -1;
00218 }
00219 else
00220 frame_prefix ="";
00221 for (uint64_t i = 1; i < frames.size(); i++)
00222 {
00223 geometry_msgs::TransformStamped ts;
00224 setIdentity(ts.transform);
00225 ts.transform.translation.x = direction * ( sqrt(2)/2 - 1);
00226 ts.transform.translation.y = direction * sqrt(2)/2;
00227 ts.transform.rotation.x = 0;
00228 ts.transform.rotation.y = 0;
00229 ts.transform.rotation.z = sin(direction * M_PI/8);
00230 ts.transform.rotation.w = cos(direction * M_PI/8);
00231 if (time > ros::Time() + (interpolation_space * .5))
00232 ts.header.stamp = time - (interpolation_space * .5);
00233 else
00234 ts.header.stamp = ros::Time();
00235
00236 ts.header.frame_id = frame_prefix + frames[i-1];
00237 if (i > 1)
00238 ts.child_frame_id = frame_prefix + frames[i];
00239 else
00240 ts.child_frame_id = frames[i];
00241 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00242 if (interpolation_space > ros::Duration())
00243 {
00244 ts.header.stamp = time + interpolation_space * .5;
00245 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00246
00247 }
00248 }
00249 }
00250 return;
00251 }
00252 else if (mode == "1")
00253 {
00254 push_back_1(children, parents, dx, dy);
00255
00256 }
00257 else if (mode =="1_v")
00258 {
00259 push_back_1(children, parents, dx, dy);
00260 push_back_v(children, parents, dx, dy);
00261 }
00262 else
00263 EXPECT_FALSE("Undefined mode for tree setup. Test harness improperly setup.");
00264
00265
00267 for (uint64_t i = 0; i < children.size(); i++)
00268 {
00269 geometry_msgs::TransformStamped ts;
00270 setIdentity(ts.transform);
00271 ts.transform.translation.x = dx[i];
00272 ts.transform.translation.y = dy[i];
00273 if (time > ros::Time() + (interpolation_space * .5))
00274 ts.header.stamp = time - (interpolation_space * .5);
00275 else
00276 ts.header.stamp = ros::Time();
00277
00278 ts.header.frame_id = parents[i];
00279 ts.child_frame_id = children[i];
00280 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00281 if (interpolation_space > ros::Duration())
00282 {
00283 ts.header.stamp = time + interpolation_space * .5;
00284 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00285
00286 }
00287 }
00288 }
00289
00290
00291 TEST(BufferCore_setTransform, NoInsertOnSelfTransform)
00292 {
00293 tf2::BufferCore mBC;
00294 geometry_msgs::TransformStamped tranStamped;
00295 setIdentity(tranStamped.transform);
00296 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00297 tranStamped.header.frame_id = "same_frame";
00298 tranStamped.child_frame_id = "same_frame";
00299 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00300 }
00301
00302 TEST(BufferCore_setTransform, NoInsertWithNan)
00303 {
00304 tf2::BufferCore mBC;
00305 geometry_msgs::TransformStamped tranStamped;
00306 setIdentity(tranStamped.transform);
00307 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00308 tranStamped.header.frame_id = "same_frame";
00309 tranStamped.child_frame_id = "other_frame";
00310 EXPECT_TRUE(mBC.setTransform(tranStamped, "authority"));
00311 tranStamped.transform.translation.x = 0.0/0.0;
00312 EXPECT_TRUE(std::isnan(tranStamped.transform.translation.x));
00313 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00314
00315 }
00316
00317 TEST(BufferCore_setTransform, NoInsertWithNoFrameID)
00318 {
00319 tf2::BufferCore mBC;
00320 geometry_msgs::TransformStamped tranStamped;
00321 setIdentity(tranStamped.transform);
00322 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00323 tranStamped.header.frame_id = "same_frame";
00324 tranStamped.child_frame_id = "";
00325 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00326 tranStamped.child_frame_id = "/";
00327 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00328
00329 }
00330
00331 TEST(BufferCore_setTransform, NoInsertWithNoParentID)
00332 {
00333 tf2::BufferCore mBC;
00334 geometry_msgs::TransformStamped tranStamped;
00335 setIdentity(tranStamped.transform);
00336 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00337 tranStamped.header.frame_id = "";
00338 tranStamped.child_frame_id = "some_frame";
00339 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00340
00341 tranStamped.header.frame_id = "/";
00342 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00343 }
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380
00381
00382
00383
00384
00385
00386
00387
00388
00389
00390
00391
00392
00393
00394
00395
00396
00397
00398
00399
00400
00401
00402
00403
00404
00405
00406
00407
00408
00409
00410
00411
00412
00413
00414
00415
00416
00417
00418
00419
00420
00421
00422
00423
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436
00437
00438
00439
00440
00441
00442
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457
00458
00459
00460
00461
00462
00463
00464
00465
00466
00467
00468
00469
00470
00471
00472
00473
00474
00475
00476
00477
00478
00479
00480
00481
00482
00483
00484
00485
00486
00487
00488
00489
00490
00491
00492
00493
00494
00495
00496
00497
00498
00499
00500
00501
00502
00503
00504
00505
00506
00507
00508
00509
00510
00511
00512
00513
00514
00515
00516
00517
00518
00519
00520
00521
00522
00523
00524
00525
00526
00527
00528
00529
00530
00531
00532
00533
00534
00535
00536
00537
00538
00539
00540
00541
00542
00543
00544
00545
00546
00547
00548
00549
00550
00551
00552
00553
00554
00555
00556
00557
00558
00559
00560
00561
00562
00563
00564
00565
00566
00567
00568
00569
00570
00571
00572
00573
00574
00575
00576
00577
00578
00579
00580
00581
00582
00583
00584
00585
00586
00587
00588
00589
00590
00591
00592
00593
00594
00595
00596
00597
00598
00599
00600
00601
00602
00603
00604
00605
00606
00607
00608
00609
00610
00611
00612
00613
00614
00615
00616
00617
00618
00619
00620
00621
00622 TEST(BufferCore_lookupTransform, i_configuration)
00623 {
00624 double epsilon = 1e-6;
00625
00626
00627
00628 rostest::Permuter permuter;
00629
00630 std::vector<ros::Time> times;
00631 times.push_back(ros::Time(1.0));
00632 times.push_back(ros::Time(10.0));
00633 times.push_back(ros::Time(0.0));
00634 ros::Time eval_time;
00635 permuter.addOptionSet(times, &eval_time);
00636
00637 std::vector<ros::Duration> durations;
00638 durations.push_back(ros::Duration(1.0));
00639 durations.push_back(ros::Duration(0.001));
00640 durations.push_back(ros::Duration(0.1));
00641 ros::Duration interpolation_space;
00642
00643
00644 std::vector<std::string> frames;
00645 frames.push_back("a");
00646 frames.push_back("b");
00647 frames.push_back("c");
00648 std::string source_frame;
00649 permuter.addOptionSet(frames, &source_frame);
00650
00651 std::string target_frame;
00652 permuter.addOptionSet(frames, &target_frame);
00653
00654 while (permuter.step())
00655 {
00656
00657 tf2::BufferCore mBC;
00658 setupTree(mBC, "i", eval_time, interpolation_space);
00659
00660 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
00661
00662 EXPECT_EQ(outpose.header.stamp, eval_time);
00663 EXPECT_EQ(outpose.header.frame_id, source_frame);
00664 EXPECT_EQ(outpose.child_frame_id, target_frame);
00665 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00666 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00667 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00668 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00669 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00670 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00671
00672
00673 if (source_frame == target_frame)
00674 {
00675 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00676 }
00677 else if ((source_frame == "a" && target_frame =="b") ||
00678 (source_frame == "b" && target_frame =="c"))
00679 {
00680 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00681 }
00682 else if ((source_frame == "b" && target_frame =="a") ||
00683 (source_frame == "c" && target_frame =="b"))
00684 {
00685 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00686 }
00687 else if (source_frame == "a" && target_frame =="c")
00688 {
00689 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00690 }
00691 else if (source_frame == "c" && target_frame =="a")
00692 {
00693 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00694 }
00695 else
00696 {
00697 EXPECT_FALSE("i configuration: Shouldn't get here");
00698 printf("source_frame %s target_frame %s time %f\n", source_frame.c_str(), target_frame.c_str(), eval_time.toSec());
00699 }
00700
00701 }
00702 }
00703
00704
00705 bool check_1_result(const geometry_msgs::TransformStamped& outpose, const std::string& source_frame, const std::string& target_frame, const ros::Time& eval_time, double epsilon)
00706 {
00707
00708 EXPECT_EQ(outpose.header.stamp, eval_time);
00709 EXPECT_EQ(outpose.header.frame_id, source_frame);
00710 EXPECT_EQ(outpose.child_frame_id, target_frame);
00711 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00712 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00713 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00714 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00715 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00716 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00717
00718
00719 if (source_frame == target_frame)
00720 {
00721 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00722 }
00723 else if (source_frame == "1" && target_frame =="2")
00724 {
00725 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00726 }
00727 else if (source_frame == "2" && target_frame =="1")
00728 {
00729 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00730 }
00731 else
00732 {
00733
00734 return false;
00735 }
00736 return true;
00737 }
00738
00739
00740 bool check_v_result(const geometry_msgs::TransformStamped& outpose, const std::string& source_frame, const std::string& target_frame, const ros::Time& eval_time, double epsilon)
00741 {
00742
00743 EXPECT_EQ(outpose.header.stamp, eval_time);
00744 EXPECT_EQ(outpose.header.frame_id, source_frame);
00745 EXPECT_EQ(outpose.child_frame_id, target_frame);
00746 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00747 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00748 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00749 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00750 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00751
00752
00753 if (source_frame == target_frame)
00754 {
00755 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00756 }
00757 else if ((source_frame == "a" && target_frame =="b") ||
00758 (source_frame == "b" && target_frame =="c"))
00759 {
00760 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00761 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00762 }
00763 else if ((source_frame == "b" && target_frame =="a") ||
00764 (source_frame == "c" && target_frame =="b"))
00765 {
00766 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00767 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00768 }
00769 else if ((source_frame == "a" && target_frame =="f") ||
00770 (source_frame == "f" && target_frame =="g"))
00771 {
00772 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00773 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00774 }
00775 else if ((source_frame == "f" && target_frame =="a") ||
00776 (source_frame == "g" && target_frame =="f"))
00777 {
00778 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00779 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00780 }
00781 else if (source_frame == "a" && target_frame =="g")
00782 {
00783 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00784 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00785 }
00786 else if (source_frame == "g" && target_frame =="a")
00787 {
00788 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00789 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00790 }
00791 else if (source_frame == "a" && target_frame =="c")
00792 {
00793 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00794 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00795 }
00796 else if (source_frame == "c" && target_frame =="a")
00797 {
00798 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00799 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00800 }
00801 else if (source_frame == "b" && target_frame =="f")
00802 {
00803 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00804 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00805 }
00806 else if (source_frame == "f" && target_frame =="b")
00807 {
00808 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00809 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00810 }
00811 else if (source_frame == "c" && target_frame =="f")
00812 {
00813 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00814 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00815 }
00816 else if (source_frame == "f" && target_frame =="c")
00817 {
00818 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00819 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00820 }
00821 else if (source_frame == "b" && target_frame =="g")
00822 {
00823 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00824 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00825 }
00826 else if (source_frame == "g" && target_frame =="b")
00827 {
00828 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00829 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00830 }
00831 else if (source_frame == "c" && target_frame =="g")
00832 {
00833 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00834 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00835 }
00836 else if (source_frame == "g" && target_frame =="c")
00837 {
00838 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00839 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00840 }
00841 else
00842 {
00843
00844 return false;
00845 }
00846 return true;
00847 }
00848
00849
00850 bool check_y_result(const geometry_msgs::TransformStamped& outpose, const std::string& source_frame, const std::string& target_frame, const ros::Time& eval_time, double epsilon)
00851 {
00852
00853 EXPECT_EQ(outpose.header.stamp, eval_time);
00854 EXPECT_EQ(outpose.header.frame_id, source_frame);
00855 EXPECT_EQ(outpose.child_frame_id, target_frame);
00856 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00857 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00858 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00859 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00860 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00861
00862
00863 if (source_frame == target_frame)
00864 {
00865 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00866 }
00867 else if ((source_frame == "a" && target_frame =="b") ||
00868 (source_frame == "b" && target_frame =="c"))
00869 {
00870 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00871 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00872 }
00873 else if ((source_frame == "b" && target_frame =="a") ||
00874 (source_frame == "c" && target_frame =="b"))
00875 {
00876 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00877 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00878 }
00879 else if ((source_frame == "b" && target_frame =="d") ||
00880 (source_frame == "d" && target_frame =="e"))
00881 {
00882 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00883 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00884 }
00885 else if ((source_frame == "d" && target_frame =="b") ||
00886 (source_frame == "e" && target_frame =="d"))
00887 {
00888 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00889 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00890 }
00891 else if (source_frame == "b" && target_frame =="e")
00892 {
00893 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00894 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00895 }
00896 else if (source_frame == "e" && target_frame =="b")
00897 {
00898 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00899 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00900 }
00901 else if (source_frame == "a" && target_frame =="c")
00902 {
00903 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00904 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00905 }
00906 else if (source_frame == "c" && target_frame =="a")
00907 {
00908 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00909 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00910 }
00911 else if (source_frame == "a" && target_frame =="d")
00912 {
00913 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00914 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00915 }
00916 else if (source_frame == "d" && target_frame =="a")
00917 {
00918 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00919 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00920 }
00921 else if (source_frame == "c" && target_frame =="d")
00922 {
00923 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00924 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00925 }
00926 else if (source_frame == "d" && target_frame =="c")
00927 {
00928 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00929 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00930 }
00931 else if (source_frame == "a" && target_frame =="e")
00932 {
00933 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00934 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00935 }
00936 else if (source_frame == "e" && target_frame =="a")
00937 {
00938 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00939 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00940 }
00941 else if (source_frame == "c" && target_frame =="e")
00942 {
00943 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00944 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00945 }
00946 else if (source_frame == "e" && target_frame =="c")
00947 {
00948 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00949 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00950 }
00951 else
00952 {
00953
00954 return false;
00955 }
00956 return true;
00957 }
00958
00959
00960 TEST(BufferCore_lookupTransform, one_link_configuration)
00961 {
00962 double epsilon = 1e-6;
00963
00964
00965
00966 rostest::Permuter permuter;
00967
00968 std::vector<ros::Time> times;
00969 times.push_back(ros::Time(1.0));
00970 times.push_back(ros::Time(10.0));
00971 times.push_back(ros::Time(0.0));
00972 ros::Time eval_time;
00973 permuter.addOptionSet(times, &eval_time);
00974
00975 std::vector<ros::Duration> durations;
00976 durations.push_back(ros::Duration(1.0));
00977 durations.push_back(ros::Duration(0.001));
00978 durations.push_back(ros::Duration(0.1));
00979 ros::Duration interpolation_space;
00980
00981
00982 std::vector<std::string> frames;
00983 frames.push_back("1");
00984 frames.push_back("2");
00985 std::string source_frame;
00986 permuter.addOptionSet(frames, &source_frame);
00987
00988 std::string target_frame;
00989 permuter.addOptionSet(frames, &target_frame);
00990
00991 while (permuter.step())
00992 {
00993
00994 tf2::BufferCore mBC;
00995 setupTree(mBC, "1", eval_time, interpolation_space);
00996
00997 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
00998
00999 EXPECT_TRUE(check_1_result(outpose, source_frame, target_frame, eval_time, epsilon));
01000 }
01001 }
01002
01003
01004 TEST(BufferCore_lookupTransform, v_configuration)
01005 {
01006 double epsilon = 1e-6;
01007
01008
01009
01010 rostest::Permuter permuter;
01011
01012 std::vector<ros::Time> times;
01013 times.push_back(ros::Time(1.0));
01014 times.push_back(ros::Time(10.0));
01015 times.push_back(ros::Time(0.0));
01016 ros::Time eval_time;
01017 permuter.addOptionSet(times, &eval_time);
01018
01019 std::vector<ros::Duration> durations;
01020 durations.push_back(ros::Duration(1.0));
01021 durations.push_back(ros::Duration(0.001));
01022 durations.push_back(ros::Duration(0.1));
01023 ros::Duration interpolation_space;
01024
01025
01026 std::vector<std::string> frames;
01027 frames.push_back("a");
01028 frames.push_back("b");
01029 frames.push_back("c");
01030 frames.push_back("f");
01031 frames.push_back("g");
01032 std::string source_frame;
01033 permuter.addOptionSet(frames, &source_frame);
01034
01035 std::string target_frame;
01036 permuter.addOptionSet(frames, &target_frame);
01037
01038 while (permuter.step())
01039 {
01040
01041 tf2::BufferCore mBC;
01042 setupTree(mBC, "v", eval_time, interpolation_space);
01043
01044 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01045
01046 EXPECT_TRUE(check_v_result(outpose, source_frame, target_frame, eval_time, epsilon));
01047 }
01048 }
01049
01050
01051 TEST(BufferCore_lookupTransform, y_configuration)
01052 {
01053 double epsilon = 1e-6;
01054
01055
01056
01057 rostest::Permuter permuter;
01058
01059 std::vector<ros::Time> times;
01060 times.push_back(ros::Time(1.0));
01061 times.push_back(ros::Time(10.0));
01062 times.push_back(ros::Time(0.0));
01063 ros::Time eval_time;
01064 permuter.addOptionSet(times, &eval_time);
01065
01066 std::vector<ros::Duration> durations;
01067 durations.push_back(ros::Duration(1.0));
01068 durations.push_back(ros::Duration(0.001));
01069 durations.push_back(ros::Duration(0.1));
01070 ros::Duration interpolation_space;
01071
01072
01073 std::vector<std::string> frames;
01074 frames.push_back("a");
01075 frames.push_back("b");
01076 frames.push_back("c");
01077 frames.push_back("d");
01078 frames.push_back("e");
01079 std::string source_frame;
01080 permuter.addOptionSet(frames, &source_frame);
01081
01082 std::string target_frame;
01083 permuter.addOptionSet(frames, &target_frame);
01084
01085 while (permuter.step())
01086 {
01087
01088 tf2::BufferCore mBC;
01089 setupTree(mBC, "y", eval_time, interpolation_space);
01090
01091 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01092
01093 EXPECT_TRUE(check_y_result(outpose, source_frame, target_frame, eval_time, epsilon));
01094 }
01095 }
01096
01097 TEST(BufferCore_lookupTransform, multi_configuration)
01098 {
01099 double epsilon = 1e-6;
01100
01101
01102
01103 rostest::Permuter permuter;
01104
01105 std::vector<ros::Time> times;
01106 times.push_back(ros::Time(1.0));
01107 times.push_back(ros::Time(10.0));
01108 times.push_back(ros::Time(0.0));
01109 ros::Time eval_time;
01110 permuter.addOptionSet(times, &eval_time);
01111
01112 std::vector<ros::Duration> durations;
01113 durations.push_back(ros::Duration(1.0));
01114 durations.push_back(ros::Duration(0.001));
01115 durations.push_back(ros::Duration(0.1));
01116 ros::Duration interpolation_space;
01117
01118
01119 std::vector<std::string> frames;
01120 frames.push_back("1");
01121 frames.push_back("2");
01122 frames.push_back("a");
01123 frames.push_back("b");
01124 frames.push_back("c");
01125 frames.push_back("f");
01126 frames.push_back("g");
01127 std::string source_frame;
01128 permuter.addOptionSet(frames, &source_frame);
01129
01130 std::string target_frame;
01131 permuter.addOptionSet(frames, &target_frame);
01132
01133 while (permuter.step())
01134 {
01135
01136 tf2::BufferCore mBC;
01137 setupTree(mBC, "1_v", eval_time, interpolation_space);
01138
01139 if (mBC.canTransform(source_frame, target_frame, eval_time))
01140 {
01141 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01142
01143 if ((source_frame == "1" || source_frame =="2") && (target_frame =="1" || target_frame == "2"))
01144 EXPECT_TRUE(check_1_result(outpose, source_frame, target_frame, eval_time, epsilon));
01145 else if ((source_frame == "a" || source_frame == "b" || source_frame == "c" || source_frame == "f" || source_frame == "g") &&
01146 (target_frame == "a" || target_frame == "b" || target_frame == "c" || target_frame == "f" || target_frame == "g"))
01147 EXPECT_TRUE(check_v_result(outpose, source_frame, target_frame, eval_time, epsilon));
01148 else
01149 EXPECT_FALSE("Frames unhandled");
01150 }
01151 else
01152 EXPECT_TRUE(((source_frame == "a" || source_frame =="b" || source_frame == "c" || source_frame == "f" || source_frame == "g") &&
01153 (target_frame == "1" || target_frame == "2") )
01154 ||
01155 ((target_frame == "a" || target_frame =="b" || target_frame == "c" || target_frame == "f" || target_frame == "g") &&
01156 (source_frame == "1" || source_frame == "2"))
01157 );
01158
01159 }
01160 }
01161
01162 #define CHECK_QUATERNION_NEAR(_q1, _x, _y, _z, _w, _epsilon) \
01163 { \
01164 btQuaternion q1(_q1.x, _q1.y, _q1.z, _q1.w); \
01165 btQuaternion q2(_x, _y, _z, _w); \
01166 double angle = q1.angle(q2); \
01167 EXPECT_TRUE(fabs(angle) < _epsilon || fabs(angle - M_PI) < _epsilon); \
01168 }
01169
01170 #define CHECK_TRANSFORMS_NEAR(_out, _expected, _eps) \
01171 EXPECT_NEAR(_out.transform.translation.x, _expected.getOrigin().x(), epsilon); \
01172 EXPECT_NEAR(_out.transform.translation.y, _expected.getOrigin().y(), epsilon); \
01173 EXPECT_NEAR(_out.transform.translation.z, _expected.getOrigin().z(), epsilon); \
01174 CHECK_QUATERNION_NEAR(_out.transform.rotation, _expected.getRotation().x(), _expected.getRotation().y(), _expected.getRotation().z(), _expected.getRotation().w(), _eps);
01175
01176
01177
01178 TEST(BufferCore_lookupTransform, compound_xfm_configuration)
01179 {
01180
01181
01182
01183
01184
01185
01186
01187
01188
01189 double epsilon = 2e-5;
01190
01191 tf2::BufferCore mBC;
01192
01193 geometry_msgs::TransformStamped tsa;
01194 tsa.header.frame_id = "root";
01195 tsa.child_frame_id = "a";
01196 tsa.transform.translation.x = 1.0;
01197 tsa.transform.translation.y = 1.0;
01198 tsa.transform.translation.z = 1.0;
01199 btQuaternion q1;
01200 q1.setEuler(0.25, .5, .75);
01201 tsa.transform.rotation.x = q1.x();
01202 tsa.transform.rotation.y = q1.y();
01203 tsa.transform.rotation.z = q1.z();
01204 tsa.transform.rotation.w = q1.w();
01205 EXPECT_TRUE(mBC.setTransform(tsa, "authority"));
01206
01207 geometry_msgs::TransformStamped tsb;
01208 tsb.header.frame_id = "root";
01209 tsb.child_frame_id = "b";
01210 tsb.transform.translation.x = -1.0;
01211 tsb.transform.translation.y = 0.0;
01212 tsb.transform.translation.z = -1.0;
01213 btQuaternion q2;
01214 q2.setEuler(1.0, 0.25, 0.5);
01215 tsb.transform.rotation.x = q2.x();
01216 tsb.transform.rotation.y = q2.y();
01217 tsb.transform.rotation.z = q2.z();
01218 tsb.transform.rotation.w = q2.w();
01219 EXPECT_TRUE(mBC.setTransform(tsb, "authority"));
01220
01221 geometry_msgs::TransformStamped tsc;
01222 tsc.header.frame_id = "b";
01223 tsc.child_frame_id = "c";
01224 tsc.transform.translation.x = 0.0;
01225 tsc.transform.translation.y = 2.0;
01226 tsc.transform.translation.z = 0.5;
01227 btQuaternion q3;
01228 q3.setEuler(0.25, .75, 1.25);
01229 tsc.transform.rotation.x = q3.x();
01230 tsc.transform.rotation.y = q3.y();
01231 tsc.transform.rotation.z = q3.z();
01232 tsc.transform.rotation.w = q3.w();
01233 EXPECT_TRUE(mBC.setTransform(tsc, "authority"));
01234
01235 geometry_msgs::TransformStamped tsd;
01236 tsd.header.frame_id = "c";
01237 tsd.child_frame_id = "d";
01238 tsd.transform.translation.x = 0.5;
01239 tsd.transform.translation.y = -1;
01240 tsd.transform.translation.z = 1.5;
01241 btQuaternion q4;
01242 q4.setEuler(-0.5, 1.0, -.75);
01243 tsd.transform.rotation.x = q4.x();
01244 tsd.transform.rotation.y = q4.y();
01245 tsd.transform.rotation.z = q4.z();
01246 tsd.transform.rotation.w = q4.w();
01247 EXPECT_TRUE(mBC.setTransform(tsd, "authority"));
01248
01249 btTransform ta, tb, tc, td, expected_ab, expected_bc, expected_cb, expected_ac, expected_ba, expected_ca, expected_ad, expected_da, expected_bd, expected_db, expected_rootd, expected_rootc;
01250 ta.setOrigin(btVector3(1.0, 1.0, 1.0));
01251 ta.setRotation(q1);
01252 tb.setOrigin(btVector3(-1.0, 0.0, -1.0));
01253 tb.setRotation(q2);
01254 tc.setOrigin(btVector3(0.0, 2.0, 0.5));
01255 tc.setRotation(q3);
01256 td.setOrigin(btVector3(0.5, -1, 1.5));
01257 td.setRotation(q4);
01258
01259
01260 expected_ab = ta.inverse() * tb;
01261 expected_ac = ta.inverse() * tb * tc;
01262 expected_ad = ta.inverse() * tb * tc * td;
01263 expected_cb = tc.inverse();
01264 expected_bc = tc;
01265 expected_bd = tc * td;
01266 expected_db = expected_bd.inverse();
01267 expected_ba = tb.inverse() * ta;
01268 expected_ca = tc.inverse() * tb.inverse() * ta;
01269 expected_da = td.inverse() * tc.inverse() * tb.inverse() * ta;
01270 expected_rootd = tb * tc * td;
01271 expected_rootc = tb * tc;
01272
01273
01274 geometry_msgs::TransformStamped out_rootc = mBC.lookupTransform("root", "c", ros::Time());
01275 CHECK_TRANSFORMS_NEAR(out_rootc, expected_rootc, epsilon);
01276
01277
01278 geometry_msgs::TransformStamped out_rootd = mBC.lookupTransform("root", "d", ros::Time());
01279 CHECK_TRANSFORMS_NEAR(out_rootd, expected_rootd, epsilon);
01280
01281
01282 geometry_msgs::TransformStamped out_ab = mBC.lookupTransform("a", "b", ros::Time());
01283 CHECK_TRANSFORMS_NEAR(out_ab, expected_ab, epsilon);
01284
01285 geometry_msgs::TransformStamped out_ba = mBC.lookupTransform("b", "a", ros::Time());
01286 CHECK_TRANSFORMS_NEAR(out_ba, expected_ba, epsilon);
01287
01288
01289 geometry_msgs::TransformStamped out_ac = mBC.lookupTransform("a", "c", ros::Time());
01290 CHECK_TRANSFORMS_NEAR(out_ac, expected_ac, epsilon);
01291
01292 geometry_msgs::TransformStamped out_ca = mBC.lookupTransform("c", "a", ros::Time());
01293 CHECK_TRANSFORMS_NEAR(out_ca, expected_ca, epsilon);
01294
01295
01296 geometry_msgs::TransformStamped out_ad = mBC.lookupTransform("a", "d", ros::Time());
01297 CHECK_TRANSFORMS_NEAR(out_ad, expected_ad, epsilon);
01298
01299 geometry_msgs::TransformStamped out_da = mBC.lookupTransform("d", "a", ros::Time());
01300 CHECK_TRANSFORMS_NEAR(out_da, expected_da, epsilon);
01301
01302
01303 geometry_msgs::TransformStamped out_cb = mBC.lookupTransform("c", "b", ros::Time());
01304 CHECK_TRANSFORMS_NEAR(out_cb, expected_cb, epsilon);
01305
01306 geometry_msgs::TransformStamped out_bc = mBC.lookupTransform("b", "c", ros::Time());
01307 CHECK_TRANSFORMS_NEAR(out_bc, expected_bc, epsilon);
01308
01309
01310 geometry_msgs::TransformStamped out_bd = mBC.lookupTransform("b", "d", ros::Time());
01311 CHECK_TRANSFORMS_NEAR(out_bd, expected_bd, epsilon);
01312
01313 geometry_msgs::TransformStamped out_db = mBC.lookupTransform("d", "b", ros::Time());
01314 CHECK_TRANSFORMS_NEAR(out_db, expected_db, epsilon);
01315 }
01316
01317
01318 TEST(BufferCore_lookupTransform, helix_configuration)
01319 {
01320 double epsilon = 2e-5;
01321
01322 tf2::BufferCore mBC;
01323
01324 ros::Time t0 = ros::Time() + ros::Duration(10);
01325 ros::Duration step = ros::Duration(0.05);
01326 ros::Duration half_step = ros::Duration(0.025);
01327 ros::Time t1 = t0 + ros::Duration(5.0);
01328
01329
01330
01331
01332
01333
01334
01335
01336
01337
01338
01339
01340
01341
01342 double theta = 0.25;
01343 double vel = 1.0;
01344
01345 for (ros::Time t = t0; t <= t1; t += step)
01346 {
01347 ros::Time t2 = t + half_step;
01348 double dt = (t - t0).toSec();
01349 double dt2 = (t2 - t0).toSec();
01350
01351 geometry_msgs::TransformStamped ts;
01352 ts.header.frame_id = "a";
01353 ts.header.stamp = t;
01354 ts.child_frame_id = "b";
01355 ts.transform.translation.z = vel * dt;
01356 ts.transform.rotation.w = 1.0;
01357 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
01358
01359 geometry_msgs::TransformStamped ts2;
01360 ts2.header.frame_id = "b";
01361 ts2.header.stamp = t;
01362 ts2.child_frame_id = "c";
01363 ts2.transform.translation.x = cos(theta * dt);
01364 ts2.transform.translation.y = sin(theta * dt);
01365 btQuaternion q;
01366 q.setEuler(0,0,theta*dt);
01367 ts2.transform.rotation.z = q.z();
01368 ts2.transform.rotation.w = q.w();
01369 EXPECT_TRUE(mBC.setTransform(ts2, "authority"));
01370
01371 geometry_msgs::TransformStamped ts3;
01372 ts3.header.frame_id = "a";
01373 ts3.header.stamp = t2;
01374 ts3.child_frame_id = "d";
01375 ts3.transform.translation.z = cos(theta * dt2);
01376 ts3.transform.rotation.w = 1.0;
01377 EXPECT_TRUE(mBC.setTransform(ts3, "authority"));
01378 }
01379
01380
01381 for (ros::Time t = t0 + half_step; t < t1; t += step)
01382 {
01383 ros::Time t2 = t + half_step;
01384 double dt = (t - t0).toSec();
01385 double dt2 = (t2 - t0).toSec();
01386
01387 geometry_msgs::TransformStamped out_ab = mBC.lookupTransform("a", "b", t);
01388 EXPECT_NEAR(out_ab.transform.translation.z, vel * dt, epsilon);
01389
01390 geometry_msgs::TransformStamped out_ac = mBC.lookupTransform("a", "c", t);
01391 EXPECT_NEAR(out_ac.transform.translation.x, cos(theta * dt), epsilon);
01392 EXPECT_NEAR(out_ac.transform.translation.y, sin(theta * dt), epsilon);
01393 EXPECT_NEAR(out_ac.transform.translation.z, vel * dt, epsilon);
01394 btQuaternion q;
01395 q.setEuler(0,0,theta*dt);
01396 CHECK_QUATERNION_NEAR(out_ac.transform.rotation, 0, 0, q.z(), q.w(), epsilon);
01397
01398 geometry_msgs::TransformStamped out_ad = mBC.lookupTransform("a", "d", t);
01399 EXPECT_NEAR(out_ad.transform.translation.z, cos(theta * dt), epsilon);
01400
01401 geometry_msgs::TransformStamped out_cd = mBC.lookupTransform("c", "d", t2);
01402 EXPECT_NEAR(out_cd.transform.translation.x, -1, epsilon);
01403 EXPECT_NEAR(out_cd.transform.translation.y, 0, epsilon);
01404 EXPECT_NEAR(out_cd.transform.translation.z, cos(theta * dt2) - vel * dt2, epsilon);
01405 btQuaternion mq;
01406 mq.setEuler(0,0,-theta*dt2);
01407 CHECK_QUATERNION_NEAR(out_cd.transform.rotation, 0, 0, mq.z(), mq.w(), epsilon);
01408 }
01409
01410
01411 for (ros::Time t = t0 + half_step; t < t1; t += (step + step))
01412 {
01413 ros::Time t2 = t + step;
01414 double dt = (t - t0).toSec();
01415 double dt2 = (t2 - t0).toSec();
01416
01417 geometry_msgs::TransformStamped out_cd2 = mBC.lookupTransform("c", t, "d", t2, "a");
01418 EXPECT_NEAR(out_cd2.transform.translation.x, -1, epsilon);
01419 EXPECT_NEAR(out_cd2.transform.translation.y, 0, epsilon);
01420 EXPECT_NEAR(out_cd2.transform.translation.z, cos(theta * dt2) - vel * dt, epsilon);
01421 btQuaternion mq2;
01422 mq2.setEuler(0,0,-theta*dt);
01423 CHECK_QUATERNION_NEAR(out_cd2.transform.rotation, 0, 0, mq2.z(), mq2.w(), epsilon);
01424 }
01425 }
01426
01427
01428 TEST(BufferCore_lookupTransform, ring_45_configuration)
01429 {
01430 double epsilon = 1e-6;
01431 rostest::Permuter permuter;
01432
01433 std::vector<ros::Time> times;
01434 times.push_back(ros::Time(1.0));
01435 times.push_back(ros::Time(10.0));
01436 times.push_back(ros::Time(0.0));
01437 ros::Time eval_time;
01438 permuter.addOptionSet(times, &eval_time);
01439
01440 std::vector<ros::Duration> durations;
01441 durations.push_back(ros::Duration(1.0));
01442 durations.push_back(ros::Duration(0.001));
01443 durations.push_back(ros::Duration(0.1));
01444 ros::Duration interpolation_space;
01445
01446
01447 std::vector<std::string> frames;
01448 frames.push_back("a");
01449 frames.push_back("b");
01450 frames.push_back("c");
01451 frames.push_back("d");
01452 frames.push_back("e");
01453 frames.push_back("f");
01454 frames.push_back("g");
01455 frames.push_back("h");
01456 frames.push_back("i");
01457
01458
01459
01460
01461
01462
01463
01464
01465 std::string source_frame;
01466 permuter.addOptionSet(frames, &source_frame);
01467
01468 std::string target_frame;
01469 permuter.addOptionSet(frames, &target_frame);
01470
01471 while (permuter.step())
01472 {
01473
01474 tf2::BufferCore mBC;
01475 setupTree(mBC, "ring_45", eval_time, interpolation_space);
01476
01477 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01478
01479
01480
01481 EXPECT_EQ(outpose.header.stamp, eval_time);
01482 EXPECT_EQ(outpose.header.frame_id, source_frame);
01483 EXPECT_EQ(outpose.child_frame_id, target_frame);
01484
01485
01486
01487
01488 if (source_frame == target_frame ||
01489 (source_frame == "a" && target_frame == "i") ||
01490 (source_frame == "i" && target_frame == "a") ||
01491 (source_frame == "a" && target_frame == "inverse_i") ||
01492 (source_frame == "inverse_i" && target_frame == "a") )
01493 {
01494
01495 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
01496 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
01497 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01498 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01499 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01500 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
01501 EXPECT_NEAR(fabs(outpose.transform.rotation.w), 1, epsilon);
01502 }
01503
01504 else if ((source_frame == "a" && target_frame =="b") ||
01505 (source_frame == "b" && target_frame =="c") ||
01506 (source_frame == "c" && target_frame =="d") ||
01507 (source_frame == "d" && target_frame =="e") ||
01508 (source_frame == "e" && target_frame =="f") ||
01509 (source_frame == "f" && target_frame =="g") ||
01510 (source_frame == "g" && target_frame =="h") ||
01511 (source_frame == "h" && target_frame =="i")
01512 )
01513 {
01514 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01515 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01516 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01517 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01518 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01519 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI/8), epsilon);
01520 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI/8), epsilon);
01521 }
01522
01523 else if ((source_frame == "b" && target_frame =="a") ||
01524 (source_frame == "c" && target_frame =="b") ||
01525 (source_frame == "d" && target_frame =="c") ||
01526 (source_frame == "e" && target_frame =="d") ||
01527 (source_frame == "f" && target_frame =="e") ||
01528 (source_frame == "g" && target_frame =="f") ||
01529 (source_frame == "h" && target_frame =="g") ||
01530 (source_frame == "i" && target_frame =="h")
01531 )
01532 {
01533 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01534 EXPECT_NEAR(outpose.transform.translation.y, -sqrt(2)/2 , epsilon);
01535 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01536 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01537 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01538 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI/8), epsilon);
01539 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI/8), epsilon);
01540 }
01541
01542 else if ((source_frame == "a" && target_frame =="c") ||
01543 (source_frame == "b" && target_frame =="d") ||
01544 (source_frame == "c" && target_frame =="e") ||
01545 (source_frame == "d" && target_frame =="f") ||
01546 (source_frame == "e" && target_frame =="g") ||
01547 (source_frame == "f" && target_frame =="h") ||
01548 (source_frame == "g" && target_frame =="i")
01549 )
01550 {
01551 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01552 EXPECT_NEAR(outpose.transform.translation.y, 1 , epsilon);
01553 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01554 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01555 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01556 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI/4), epsilon);
01557 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI/4), epsilon);
01558 }
01559
01560 else if ((source_frame == "c" && target_frame =="a") ||
01561 (source_frame == "d" && target_frame =="b") ||
01562 (source_frame == "e" && target_frame =="c") ||
01563 (source_frame == "f" && target_frame =="d") ||
01564 (source_frame == "g" && target_frame =="e") ||
01565 (source_frame == "h" && target_frame =="f") ||
01566 (source_frame == "i" && target_frame =="g")
01567 )
01568 {
01569 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01570 EXPECT_NEAR(outpose.transform.translation.y, -1 , epsilon);
01571 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01572 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01573 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01574 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI/4), epsilon);
01575 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI/4), epsilon);
01576 }
01577
01578 else if ((source_frame == "a" && target_frame =="d") ||
01579 (source_frame == "b" && target_frame =="e") ||
01580 (source_frame == "c" && target_frame =="f") ||
01581 (source_frame == "d" && target_frame =="g") ||
01582 (source_frame == "e" && target_frame =="h") ||
01583 (source_frame == "f" && target_frame =="i")
01584 )
01585 {
01586 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2)/2, epsilon);
01587 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01588 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01589 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01590 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01591 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*3/8), epsilon);
01592 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*3/8), epsilon);
01593 }
01594
01595 else if ((target_frame == "a" && source_frame =="d") ||
01596 (target_frame == "b" && source_frame =="e") ||
01597 (target_frame == "c" && source_frame =="f") ||
01598 (target_frame == "d" && source_frame =="g") ||
01599 (target_frame == "e" && source_frame =="h") ||
01600 (target_frame == "f" && source_frame =="i")
01601 )
01602 {
01603 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2)/2, epsilon);
01604 EXPECT_NEAR(outpose.transform.translation.y, - sqrt(2)/2 , epsilon);
01605 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01606 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01607 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01608 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*3/8), epsilon);
01609 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*3/8), epsilon);
01610 }
01611
01612 else if ((source_frame == "a" && target_frame =="e") ||
01613 (source_frame == "b" && target_frame =="f") ||
01614 (source_frame == "c" && target_frame =="g") ||
01615 (source_frame == "d" && target_frame =="h") ||
01616 (source_frame == "e" && target_frame =="i")
01617 )
01618 {
01619 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
01620 EXPECT_NEAR(outpose.transform.translation.y, 0 , epsilon);
01621 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01622 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01623 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01624 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI/2), epsilon);
01625 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI/2), epsilon);
01626 }
01627
01628 else if ((target_frame == "a" && source_frame =="e") ||
01629 (target_frame == "b" && source_frame =="f") ||
01630 (target_frame == "c" && source_frame =="g") ||
01631 (target_frame == "d" && source_frame =="h") ||
01632 (target_frame == "e" && source_frame =="i")
01633 )
01634 {
01635 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
01636 EXPECT_NEAR(outpose.transform.translation.y, 0 , epsilon);
01637 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01638 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01639 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01640 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI/2), epsilon);
01641 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI/2), epsilon);
01642 }
01643
01644 else if ((source_frame == "a" && target_frame =="f") ||
01645 (source_frame == "b" && target_frame =="g") ||
01646 (source_frame == "c" && target_frame =="h") ||
01647 (source_frame == "d" && target_frame =="i")
01648 )
01649 {
01650 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2) /2, epsilon);
01651 EXPECT_NEAR(outpose.transform.translation.y, - sqrt(2) /2 , epsilon);
01652 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01653 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01654 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01655 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*5/8), epsilon);
01656 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*5/8), epsilon);
01657 }
01658
01659 else if ((target_frame == "a" && source_frame =="f") ||
01660 (target_frame == "b" && source_frame =="g") ||
01661 (target_frame == "c" && source_frame =="h") ||
01662 (target_frame == "d" && source_frame =="i")
01663 )
01664 {
01665 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2)/2, epsilon);
01666 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01667 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01668 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01669 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01670 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*5/8), epsilon);
01671 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*5/8), epsilon);
01672 }
01673
01674 else if ((source_frame == "a" && target_frame =="g") ||
01675 (source_frame == "b" && target_frame =="h") ||
01676 (source_frame == "c" && target_frame =="i")
01677 )
01678 {
01679 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01680 EXPECT_NEAR(outpose.transform.translation.y, -1 , epsilon);
01681 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01682 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01683 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01684 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*6/8), epsilon);
01685 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*6/8), epsilon);
01686 }
01687
01688 else if ((target_frame == "a" && source_frame =="g") ||
01689 (target_frame == "b" && source_frame =="h") ||
01690 (target_frame == "c" && source_frame =="i")
01691 )
01692 {
01693 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01694 EXPECT_NEAR(outpose.transform.translation.y, 1 , epsilon);
01695 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01696 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01697 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01698 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*6/8), epsilon);
01699 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*6/8), epsilon);
01700 }
01701
01702 else if ((source_frame == "a" && target_frame =="h") ||
01703 (source_frame == "b" && target_frame =="i")
01704 )
01705 {
01706 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01707 EXPECT_NEAR(outpose.transform.translation.y, -sqrt(2)/2 , epsilon);
01708 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01709 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01710 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01711 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*7/8), epsilon);
01712 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*7/8), epsilon);
01713 }
01714
01715 else if ((target_frame == "a" && source_frame =="h") ||
01716 (target_frame == "b" && source_frame =="i")
01717 )
01718 {
01719 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01720 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01721 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01722 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01723 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01724 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*7/8), epsilon);
01725 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*7/8), epsilon);
01726 }
01727 else
01728 {
01729 EXPECT_FALSE("Ring_45 testing Shouldn't get here");
01730 printf("source_frame %s target_frame %s time %f\n", source_frame.c_str(), target_frame.c_str(), eval_time.toSec());
01731 }
01732
01733 }
01734 }
01735
01736 TEST(BufferCore_lookupTransform, invalid_arguments)
01737 {
01738 tf2::BufferCore mBC;
01739
01740 setupTree(mBC, "i", ros::Time(1.0));
01741
01742 EXPECT_NO_THROW(mBC.lookupTransform("b", "a", ros::Time()));
01743
01744
01745 EXPECT_THROW(mBC.lookupTransform("", "a", ros::Time()), tf2::InvalidArgumentException);
01746 EXPECT_THROW(mBC.lookupTransform("b", "", ros::Time()), tf2::InvalidArgumentException);
01747
01748
01749 EXPECT_THROW(mBC.lookupTransform("/b", "a", ros::Time()), tf2::InvalidArgumentException);
01750 EXPECT_THROW(mBC.lookupTransform("b", "/a", ros::Time()), tf2::InvalidArgumentException);
01751
01752 };
01753
01754 TEST(BufferCore_canTransform, invalid_arguments)
01755 {
01756 tf2::BufferCore mBC;
01757
01758 setupTree(mBC, "i", ros::Time(1.0));
01759
01760 EXPECT_TRUE(mBC.canTransform("b", "a", ros::Time()));
01761
01762
01763
01764 EXPECT_FALSE(mBC.canTransform("", "a", ros::Time()));
01765 EXPECT_FALSE(mBC.canTransform("b", "", ros::Time()));
01766
01767
01768 EXPECT_FALSE(mBC.canTransform("/b", "a", ros::Time()));
01769 EXPECT_FALSE(mBC.canTransform("b", "/a", ros::Time()));
01770
01771 };
01772
01773 struct TransformableHelper
01774 {
01775 TransformableHelper()
01776 : called(false)
01777 {}
01778
01779 void callback(tf2::TransformableRequestHandle request_handle, const std::string& target_frame, const std::string& source_frame,
01780 ros::Time time, tf2::TransformableResult result)
01781 {
01782 called = true;
01783 }
01784
01785 bool called;
01786 };
01787
01788 TEST(BufferCore_transformableCallbacks, alreadyTransformable)
01789 {
01790 tf2::BufferCore b;
01791 TransformableHelper h;
01792
01793 geometry_msgs::TransformStamped t;
01794 t.header.stamp = ros::Time(1);
01795 t.header.frame_id = "a";
01796 t.child_frame_id = "b";
01797 t.transform.rotation.w = 1.0;
01798 b.setTransform(t, "me");
01799
01800 tf2::TransformableCallbackHandle cb_handle = b.addTransformableCallback(boost::bind(&TransformableHelper::callback, &h, _1, _2, _3, _4, _5));
01801 EXPECT_EQ(b.addTransformableRequest(cb_handle, "a", "b", ros::Time(1)), 0U);
01802 }
01803
01804 TEST(BufferCore_transformableCallbacks, waitForNewTransform)
01805 {
01806 tf2::BufferCore b;
01807 TransformableHelper h;
01808 tf2::TransformableCallbackHandle cb_handle = b.addTransformableCallback(boost::bind(&TransformableHelper::callback, &h, _1, _2, _3, _4, _5));
01809 EXPECT_GT(b.addTransformableRequest(cb_handle, "a", "b", ros::Time(10)), 0U);
01810
01811 geometry_msgs::TransformStamped t;
01812 for (uint32_t i = 1; i <= 10; ++i)
01813 {
01814 t.header.stamp = ros::Time(i);
01815 t.header.frame_id = "a";
01816 t.child_frame_id = "b";
01817 t.transform.rotation.w = 1.0;
01818 b.setTransform(t, "me");
01819
01820 if (i < 10)
01821 {
01822 ASSERT_FALSE(h.called);
01823 }
01824 else
01825 {
01826 ASSERT_TRUE(h.called);
01827 }
01828 }
01829 }
01830
01831 TEST(BufferCore_transformableCallbacks, waitForOldTransform)
01832 {
01833 tf2::BufferCore b;
01834 TransformableHelper h;
01835 tf2::TransformableCallbackHandle cb_handle = b.addTransformableCallback(boost::bind(&TransformableHelper::callback, &h, _1, _2, _3, _4, _5));
01836 EXPECT_GT(b.addTransformableRequest(cb_handle, "a", "b", ros::Time(1)), 0U);
01837
01838 geometry_msgs::TransformStamped t;
01839 for (uint32_t i = 10; i > 0; --i)
01840 {
01841 t.header.stamp = ros::Time(i);
01842 t.header.frame_id = "a";
01843 t.child_frame_id = "b";
01844 t.transform.rotation.w = 1.0;
01845 b.setTransform(t, "me");
01846
01847 if (i > 1)
01848 {
01849 ASSERT_FALSE(h.called);
01850 }
01851 else
01852 {
01853 ASSERT_TRUE(h.called);
01854 }
01855 }
01856 }
01857
01858
01859
01860
01861
01862
01863
01864
01865
01866
01867
01868
01869
01870
01871
01872
01873
01874
01875
01876
01877
01878
01879
01880
01881
01882
01883
01884
01885
01886
01887
01888
01889
01890
01891
01892
01893
01894
01895
01896
01897
01898
01899
01900
01901
01902
01903
01904
01905
01906
01907
01908
01909
01910
01911
01912
01913
01914
01915
01916
01917
01918
01919
01920
01921
01922
01923
01924
01925
01926
01927
01928
01929
01930
01931
01932
01933
01934
01935
01936
01937
01938
01939
01940
01941
01942
01943
01944
01945
01946
01947
01948
01949
01950
01951
01952
01953
01954
01955
01956
01957
01958
01959
01960
01961
01962
01963
01964
01965
01966
01967
01968
01969
01970
01971
01972
01973
01974
01975
01976
01977
01978
01979
01980
01981
01982
01983
01984
01985
01986
01987
01988
01989
01990
01991
01992
01993
01994
01995
01996
01997
01998
01999
02000
02001
02002
02003
02004
02005
02006
02007
02008
02009
02010
02011
02012
02013
02014
02015
02016
02017
02018
02019
02020
02021
02022
02023
02024
02025
02026
02027
02028
02029
02030
02031
02032
02033
02034
02035
02036
02037
02038
02039
02040
02041
02042
02043
02044
02045
02046
02047
02048
02049
02050
02051
02052
02053
02054
02055
02056
02057
02058
02059
02060
02061
02062
02063
02064
02065
02066
02067
02068
02069
02070
02071
02072
02073
02074
02075
02076
02077
02078
02079
02080
02081
02082
02083
02084
02085
02086
02087
02088
02089
02090
02091
02092
02093
02094
02095
02096
02097
02098
02099
02100
02101
02102
02103
02104
02105
02106
02107
02108
02109
02110
02111
02112
02113
02114
02115
02116
02117
02118
02119
02120
02121
02122
02123
02124
02125
02126
02127
02128
02129
02130
02131
02132
02133
02134
02135
02136
02137
02138
02139
02140
02141
02142
02143
02144
02145
02146
02147
02148
02149
02150
02151
02152
02153
02154
02155
02156
02157
02158
02159
02160
02161
02162
02163
02164
02165
02166
02167
02168
02169
02170
02171
02172
02173
02174
02175
02176
02177
02178
02179
02180
02181
02182
02183
02184
02185
02186
02187
02188
02189
02190
02191
02192
02193
02194
02195
02196
02197
02198
02199
02200
02201
02202
02203
02204
02205
02206
02207
02208
02209
02210
02211
02212
02213
02214
02215
02216
02217
02218
02219
02220
02221
02222
02223
02224
02225
02226
02227
02228
02229
02230
02231
02232
02233
02234
02235
02236
02237
02238
02239
02240
02241
02242
02243
02244
02245
02246
02247
02248
02249
02250
02251
02252
02253
02254
02255
02256
02257
02258
02259
02260
02261
02262
02263
02264
02265
02266
02267
02268
02269
02270
02271
02272
02273
02274
02275
02276
02277
02278
02279
02280
02281
02282
02283
02284
02285
02286
02287
02288
02289
02290
02291
02292
02293
02294
02295
02296
02297
02298
02299
02300
02301
02302
02303
02304
02305
02306
02307
02308
02309
02310
02311
02312
02313
02314
02315
02316
02317
02318
02319
02320
02321
02322
02323
02324
02325
02326
02327
02328
02329
02330
02331
02332
02333
02334
02335
02336
02337
02338
02339
02340
02341
02342
02343
02344
02345
02346
02347
02348
02349
02350
02351
02352
02353
02354
02355
02356
02357
02358
02359
02360
02361
02362
02363
02364
02365
02366
02367
02368
02369
02370
02371
02372
02373
02374
02375
02376
02377
02378
02379
02380
02381
02382
02383
02384
02385
02386
02387
02388
02389
02390
02391
02392
02393
02394
02395
02396
02397
02398
02399
02400
02401
02402
02403
02404
02405
02406
02407
02408
02409
02410
02411
02412
02413
02414
02415
02416
02417
02418
02419
02420
02421
02422
02423
02424
02425
02426
02427
02428
02429
02430
02431
02432
02433
02434
02435
02436
02437
02438
02439
02440
02441
02442
02443
02444
02445
02446
02447
02448
02449
02450
02451
02452
02453
02454
02455
02456
02457
02458
02459
02460
02461
02462
02463
02464
02465
02466
02467
02468
02469
02470
02471
02472
02473
02474
02475
02476
02477
02478
02479
02480
02481
02482
02483
02484
02485
02486
02487
02488
02489
02490
02491
02492
02493
02494
02495
02496
02497
02498
02499
02500
02501
02502
02503
02504
02505
02506
02507
02508
02509
02510
02511
02512
02513
02514
02515
02516
02517
02518
02519
02520
02521
02522
02523
02524
02525
02526
02527
02528
02529
02530
02531
02532
02533
02534
02535
02536
02537
02538
02539
02540
02541
02542
02543
02544
02545
02546
02547
02548
02549
02550
02551
02552
02553
02554
02555
02556
02557
02558
02559
02560
02561
02562
02563
02564
02565
02566
02567
02568
02569
02570
02571
02572
02573
02574
02575
02576
02577
02578
02579
02580
02581
02582
02583
02584
02585
02586
02587
02588
02589
02590
02591
02592
02593
02594
02595
02596
02597
02598
02599
02600
02601
02602
02603
02604
02605
02606
02607
02608
02609
02610
02611
02612
02613
02614
02615
02616
02617
02618
02619
02620
02621
02622
02623
02624
02625
02626
02627
02628
02629
02630
02631
02632
02633
02634
02635
02636
02637
02638
02639
02640
02641
02642
02643
02644
02645
02646
02647
02648
02649
02650
02651
02652
02653
02654
02655
02656
02657
02658
02659
02660
02661
02662
02663
02664
02665
02666
02667
02668
02669
02670
02671
02672
02673
02674
02675
02676
02677
02678
02679
02680
02681
02682
02683
02684
02685
02686
02687
02688
02689
02690
02691
02692
02693
02694
02695
02696
02697
02698
02699
02700
02701
02702
02703
02704
02705
02706
02707
02708
02709
02710
02711
02712
02713
02714
02715
02716
02717
02718
02719
02720
02721
02722
02723
02724
02725
02726
02727
02728
02729
02730
02731
02732
02733
02734
02735
02736
02737
02738
02739
02740
02741
02742
02743
02744
02745
02746
02747
02748
02749
02750
02751
02752
02753
02754
02755
02756
02757
02758
02759
02760
02761
02762
02763
02764
02765
02766
02767
02768
02769
02770
02771
02772
02773
02774
02775
02776
02777
02778
02779
02780
02781
02782
02783
02784
02785
02786
02787
02788
02789
02790
02791
02792
02793
02794
02795
02796
02797
02798
02799
02800
02801
02802
02803
02804
02805
02806
02807
02808
02809
02810
02811
02812 int main(int argc, char **argv){
02813 testing::InitGoogleTest(&argc, argv);
02814 ros::Time::init();
02815 ros::init(argc, argv, "tf_unittest");
02816 return RUN_ALL_TESTS();
02817 }