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 "rostest/permuter.h"
00037
00038 void seed_rand()
00039 {
00040
00041 timeval temp_time_struct;
00042 gettimeofday(&temp_time_struct,NULL);
00043 srand(temp_time_struct.tv_usec);
00044 };
00045
00046 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
00047 {
00048 seed_rand();
00049 for ( uint64_t i = 0; i < runs ; i++ )
00050 {
00051 xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00052 yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00053 zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00054 }
00055 }
00056
00057
00058 void setIdentity(geometry_msgs::Transform& trans)
00059 {
00060 trans.translation.x = 0;
00061 trans.translation.y = 0;
00062 trans.translation.z = 0;
00063 trans.rotation.x = 0;
00064 trans.rotation.y = 0;
00065 trans.rotation.z = 0;
00066 trans.rotation.w = 1;
00067 }
00068
00069
00070 void push_back_i(std::vector<std::string>& children, std::vector<std::string>& parents,
00071 std::vector<double>& dx, std::vector<double>& dy)
00072 {
00073
00074
00075
00076
00077
00078
00079
00080
00081 children.push_back("b");
00082 parents.push_back("a");
00083 dx.push_back(1.0);
00084 dy.push_back(0.0);
00085 children.push_back("c");
00086 parents.push_back("b");
00087 dx.push_back(1.0);
00088 dy.push_back(0.0);
00089 }
00090
00091
00092 void push_back_y(std::vector<std::string>& children, std::vector<std::string>& parents,
00093 std::vector<double>& dx, std::vector<double>& dy)
00094 {
00095
00096
00097
00098
00099
00100
00101
00102
00103 children.push_back("b");
00104 parents.push_back("a");
00105 dx.push_back(1.0);
00106 dy.push_back(0.0);
00107
00108 children.push_back("c");
00109 parents.push_back("b");
00110 dx.push_back(1.0);
00111 dy.push_back(0.0);
00112
00113 children.push_back("d");
00114 parents.push_back("b");
00115 dx.push_back(0.0);
00116 dy.push_back(1.0);
00117
00118 children.push_back("e");
00119 parents.push_back("d");
00120 dx.push_back(0.0);
00121 dy.push_back(1.0);
00122 }
00123
00124 void push_back_v(std::vector<std::string>& children, std::vector<std::string>& parents,
00125 std::vector<double>& dx, std::vector<double>& dy)
00126 {
00127
00128
00129
00130
00131
00132
00133
00134
00135 children.push_back("b");
00136 parents.push_back("a");
00137 dx.push_back(1.0);
00138 dy.push_back(0.0);
00139
00140 children.push_back("c");
00141 parents.push_back("b");
00142 dx.push_back(1.0);
00143 dy.push_back(0.0);
00144
00145 children.push_back("f");
00146 parents.push_back("a");
00147 dx.push_back(0.0);
00148 dy.push_back(1.0);
00149
00150 children.push_back("g");
00151 parents.push_back("f");
00152 dx.push_back(0.0);
00153 dy.push_back(1.0);
00154
00155 }
00156
00157 void push_back_1(std::vector<std::string>& children, std::vector<std::string>& parents,
00158 std::vector<double>& dx, std::vector<double>& dy)
00159 {
00160 children.push_back("2");
00161 parents.push_back("1");
00162 dx.push_back(1.0);
00163 dy.push_back(0.0);
00164 }
00165
00166 void setupTree(tf2::BufferCore& mBC, const std::string& mode, const ros::Time & time, const ros::Duration& interpolation_space = ros::Duration())
00167 {
00168 ROS_DEBUG("Clearing Buffer Core for new test setup");
00169 mBC.clear();
00170
00171 ROS_DEBUG("Setting up test tree for formation %s", mode.c_str());
00172
00173 std::vector<std::string> children;
00174 std::vector<std::string> parents;
00175 std::vector<double> dx, dy;
00176
00177 if (mode == "i")
00178 {
00179 push_back_i(children, parents, dx, dy);
00180 }
00181 else if (mode == "y")
00182 {
00183 push_back_y(children, parents, dx, dy);
00184 }
00185
00186 else if (mode == "v")
00187 {
00188 push_back_v(children, parents, dx, dy);
00189 }
00190
00191 else if (mode == "ring_45")
00192 {
00193
00194
00195 std::vector<std::string> frames;
00196
00197
00198
00199 frames.push_back("a");
00200 frames.push_back("b");
00201 frames.push_back("c");
00202 frames.push_back("d");
00203 frames.push_back("e");
00204 frames.push_back("f");
00205 frames.push_back("g");
00206 frames.push_back("h");
00207 frames.push_back("i");
00208
00209 for (uint8_t iteration = 0; iteration < 2; ++iteration)
00210 {
00211 double direction = 1;
00212 std::string frame_prefix;
00213 if (iteration == 0)
00214 {
00215 frame_prefix = "inverse_";
00216 direction = -1;
00217 }
00218 else
00219 frame_prefix ="";
00220 for (uint64_t i = 1; i < frames.size(); i++)
00221 {
00222 geometry_msgs::TransformStamped ts;
00223 setIdentity(ts.transform);
00224 ts.transform.translation.x = direction * ( sqrt(2)/2 - 1);
00225 ts.transform.translation.y = direction * sqrt(2)/2;
00226 ts.transform.rotation.x = 0;
00227 ts.transform.rotation.y = 0;
00228 ts.transform.rotation.z = sin(direction * M_PI/8);
00229 ts.transform.rotation.w = cos(direction * M_PI/8);
00230 if (time > ros::Time() + (interpolation_space * .5))
00231 ts.header.stamp = time - (interpolation_space * .5);
00232 else
00233 ts.header.stamp = ros::Time();
00234
00235 ts.header.frame_id = frame_prefix + frames[i-1];
00236 if (i > 1)
00237 ts.child_frame_id = frame_prefix + frames[i];
00238 else
00239 ts.child_frame_id = frames[i];
00240 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00241 if (interpolation_space > ros::Duration())
00242 {
00243 ts.header.stamp = time + interpolation_space * .5;
00244 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00245
00246 }
00247 }
00248 }
00249 return;
00250 }
00251 else if (mode == "1")
00252 {
00253 push_back_1(children, parents, dx, dy);
00254
00255 }
00256 else if (mode =="1_v")
00257 {
00258 push_back_1(children, parents, dx, dy);
00259 push_back_v(children, parents, dx, dy);
00260 }
00261 else
00262 EXPECT_FALSE("Undefined mode for tree setup. Test harness improperly setup.");
00263
00264
00266 for (uint64_t i = 0; i < children.size(); i++)
00267 {
00268 geometry_msgs::TransformStamped ts;
00269 setIdentity(ts.transform);
00270 ts.transform.translation.x = dx[i];
00271 ts.transform.translation.y = dy[i];
00272 if (time > ros::Time() + (interpolation_space * .5))
00273 ts.header.stamp = time - (interpolation_space * .5);
00274 else
00275 ts.header.stamp = ros::Time();
00276
00277 ts.header.frame_id = parents[i];
00278 ts.child_frame_id = children[i];
00279 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00280 if (interpolation_space > ros::Duration())
00281 {
00282 ts.header.stamp = time + interpolation_space * .5;
00283 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
00284
00285 }
00286 }
00287 }
00288
00289
00290 TEST(BufferCore_setTransform, NoInsertOnSelfTransform)
00291 {
00292 tf2::BufferCore mBC;
00293 geometry_msgs::TransformStamped tranStamped;
00294 setIdentity(tranStamped.transform);
00295 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00296 tranStamped.header.frame_id = "same_frame";
00297 tranStamped.child_frame_id = "same_frame";
00298 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00299 }
00300
00301 TEST(BufferCore_setTransform, NoInsertWithNan)
00302 {
00303 tf2::BufferCore mBC;
00304 geometry_msgs::TransformStamped tranStamped;
00305 setIdentity(tranStamped.transform);
00306 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00307 tranStamped.header.frame_id = "same_frame";
00308 tranStamped.child_frame_id = "other_frame";
00309 EXPECT_TRUE(mBC.setTransform(tranStamped, "authority"));
00310 tranStamped.transform.translation.x = 0.0/0.0;
00311 EXPECT_TRUE(std::isnan(tranStamped.transform.translation.x));
00312 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00313
00314 }
00315
00316 TEST(BufferCore_setTransform, NoInsertWithNoFrameID)
00317 {
00318 tf2::BufferCore mBC;
00319 geometry_msgs::TransformStamped tranStamped;
00320 setIdentity(tranStamped.transform);
00321 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00322 tranStamped.header.frame_id = "same_frame";
00323 tranStamped.child_frame_id = "";
00324 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00325 tranStamped.child_frame_id = "/";
00326 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00327
00328 }
00329
00330 TEST(BufferCore_setTransform, NoInsertWithNoParentID)
00331 {
00332 tf2::BufferCore mBC;
00333 geometry_msgs::TransformStamped tranStamped;
00334 setIdentity(tranStamped.transform);
00335 tranStamped.header.stamp = ros::Time().fromNSec(10.0);
00336 tranStamped.header.frame_id = "";
00337 tranStamped.child_frame_id = "some_frame";
00338 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00339
00340 tranStamped.header.frame_id = "/";
00341 EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
00342 }
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 TEST(BufferCore_lookupTransform, i_configuration)
00622 {
00623 double epsilon = 1e-6;
00624
00625
00626
00627 rostest::Permuter permuter;
00628
00629 std::vector<ros::Time> times;
00630 times.push_back(ros::Time(1.0));
00631 times.push_back(ros::Time(10.0));
00632 times.push_back(ros::Time(0.0));
00633 ros::Time eval_time;
00634 permuter.addOptionSet(times, &eval_time);
00635
00636 std::vector<ros::Duration> durations;
00637 durations.push_back(ros::Duration(1.0));
00638 durations.push_back(ros::Duration(0.001));
00639 durations.push_back(ros::Duration(0.1));
00640 ros::Duration interpolation_space;
00641
00642
00643 std::vector<std::string> frames;
00644 frames.push_back("a");
00645 frames.push_back("b");
00646 frames.push_back("c");
00647 std::string source_frame;
00648 permuter.addOptionSet(frames, &source_frame);
00649
00650 std::string target_frame;
00651 permuter.addOptionSet(frames, &target_frame);
00652
00653 while (permuter.step())
00654 {
00655
00656 tf2::BufferCore mBC;
00657 setupTree(mBC, "i", eval_time, interpolation_space);
00658
00659 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
00660
00661 EXPECT_EQ(outpose.header.stamp, eval_time);
00662 EXPECT_EQ(outpose.header.frame_id, source_frame);
00663 EXPECT_EQ(outpose.child_frame_id, target_frame);
00664 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00665 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00666 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00667 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00668 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00669 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00670
00671
00672 if (source_frame == target_frame)
00673 {
00674 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00675 }
00676 else if ((source_frame == "a" && target_frame =="b") ||
00677 (source_frame == "b" && target_frame =="c"))
00678 {
00679 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00680 }
00681 else if ((source_frame == "b" && target_frame =="a") ||
00682 (source_frame == "c" && target_frame =="b"))
00683 {
00684 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00685 }
00686 else if (source_frame == "a" && target_frame =="c")
00687 {
00688 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00689 }
00690 else if (source_frame == "c" && target_frame =="a")
00691 {
00692 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00693 }
00694 else
00695 {
00696 EXPECT_FALSE("i configuration: Shouldn't get here");
00697 printf("source_frame %s target_frame %s time %f\n", source_frame.c_str(), target_frame.c_str(), eval_time.toSec());
00698 }
00699
00700 }
00701 }
00702
00703
00704 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)
00705 {
00706
00707 EXPECT_EQ(outpose.header.stamp, eval_time);
00708 EXPECT_EQ(outpose.header.frame_id, source_frame);
00709 EXPECT_EQ(outpose.child_frame_id, target_frame);
00710 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00711 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00712 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00713 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00714 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00715 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00716
00717
00718 if (source_frame == target_frame)
00719 {
00720 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00721 }
00722 else if (source_frame == "1" && target_frame =="2")
00723 {
00724 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00725 }
00726 else if (source_frame == "2" && target_frame =="1")
00727 {
00728 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00729 }
00730 else
00731 {
00732
00733 return false;
00734 }
00735 return true;
00736 }
00737
00738
00739 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)
00740 {
00741
00742 EXPECT_EQ(outpose.header.stamp, eval_time);
00743 EXPECT_EQ(outpose.header.frame_id, source_frame);
00744 EXPECT_EQ(outpose.child_frame_id, target_frame);
00745 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00746 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00747 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00748 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00749 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00750
00751
00752 if (source_frame == target_frame)
00753 {
00754 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00755 }
00756 else if ((source_frame == "a" && target_frame =="b") ||
00757 (source_frame == "b" && target_frame =="c"))
00758 {
00759 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00760 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00761 }
00762 else if ((source_frame == "b" && target_frame =="a") ||
00763 (source_frame == "c" && target_frame =="b"))
00764 {
00765 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00766 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00767 }
00768 else if ((source_frame == "a" && target_frame =="f") ||
00769 (source_frame == "f" && target_frame =="g"))
00770 {
00771 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00772 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00773 }
00774 else if ((source_frame == "f" && target_frame =="a") ||
00775 (source_frame == "g" && target_frame =="f"))
00776 {
00777 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00778 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00779 }
00780 else if (source_frame == "a" && target_frame =="g")
00781 {
00782 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00783 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00784 }
00785 else if (source_frame == "g" && target_frame =="a")
00786 {
00787 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00788 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00789 }
00790 else if (source_frame == "a" && target_frame =="c")
00791 {
00792 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00793 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00794 }
00795 else if (source_frame == "c" && target_frame =="a")
00796 {
00797 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00798 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00799 }
00800 else if (source_frame == "b" && target_frame =="f")
00801 {
00802 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00803 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00804 }
00805 else if (source_frame == "f" && target_frame =="b")
00806 {
00807 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00808 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00809 }
00810 else if (source_frame == "c" && target_frame =="f")
00811 {
00812 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00813 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00814 }
00815 else if (source_frame == "f" && target_frame =="c")
00816 {
00817 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00818 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00819 }
00820 else if (source_frame == "b" && target_frame =="g")
00821 {
00822 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00823 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00824 }
00825 else if (source_frame == "g" && target_frame =="b")
00826 {
00827 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00828 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00829 }
00830 else if (source_frame == "c" && target_frame =="g")
00831 {
00832 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00833 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00834 }
00835 else if (source_frame == "g" && target_frame =="c")
00836 {
00837 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00838 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00839 }
00840 else
00841 {
00842
00843 return false;
00844 }
00845 return true;
00846 }
00847
00848
00849 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)
00850 {
00851
00852 EXPECT_EQ(outpose.header.stamp, eval_time);
00853 EXPECT_EQ(outpose.header.frame_id, source_frame);
00854 EXPECT_EQ(outpose.child_frame_id, target_frame);
00855 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
00856 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
00857 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
00858 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
00859 EXPECT_NEAR(outpose.transform.rotation.w, 1, epsilon);
00860
00861
00862 if (source_frame == target_frame)
00863 {
00864 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00865 }
00866 else if ((source_frame == "a" && target_frame =="b") ||
00867 (source_frame == "b" && target_frame =="c"))
00868 {
00869 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00870 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00871 }
00872 else if ((source_frame == "b" && target_frame =="a") ||
00873 (source_frame == "c" && target_frame =="b"))
00874 {
00875 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00876 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00877 }
00878 else if ((source_frame == "b" && target_frame =="d") ||
00879 (source_frame == "d" && target_frame =="e"))
00880 {
00881 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00882 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00883 }
00884 else if ((source_frame == "d" && target_frame =="b") ||
00885 (source_frame == "e" && target_frame =="d"))
00886 {
00887 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00888 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00889 }
00890 else if (source_frame == "b" && target_frame =="e")
00891 {
00892 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00893 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00894 }
00895 else if (source_frame == "e" && target_frame =="b")
00896 {
00897 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
00898 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00899 }
00900 else if (source_frame == "a" && target_frame =="c")
00901 {
00902 EXPECT_NEAR(outpose.transform.translation.x, 2, epsilon);
00903 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00904 }
00905 else if (source_frame == "c" && target_frame =="a")
00906 {
00907 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
00908 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
00909 }
00910 else if (source_frame == "a" && target_frame =="d")
00911 {
00912 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00913 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00914 }
00915 else if (source_frame == "d" && target_frame =="a")
00916 {
00917 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00918 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00919 }
00920 else if (source_frame == "c" && target_frame =="d")
00921 {
00922 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00923 EXPECT_NEAR(outpose.transform.translation.y, 1, epsilon);
00924 }
00925 else if (source_frame == "d" && target_frame =="c")
00926 {
00927 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00928 EXPECT_NEAR(outpose.transform.translation.y, -1, epsilon);
00929 }
00930 else if (source_frame == "a" && target_frame =="e")
00931 {
00932 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00933 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00934 }
00935 else if (source_frame == "e" && target_frame =="a")
00936 {
00937 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00938 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00939 }
00940 else if (source_frame == "c" && target_frame =="e")
00941 {
00942 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
00943 EXPECT_NEAR(outpose.transform.translation.y, 2, epsilon);
00944 }
00945 else if (source_frame == "e" && target_frame =="c")
00946 {
00947 EXPECT_NEAR(outpose.transform.translation.x, 1, epsilon);
00948 EXPECT_NEAR(outpose.transform.translation.y, -2, epsilon);
00949 }
00950 else
00951 {
00952
00953 return false;
00954 }
00955 return true;
00956 }
00957
00958
00959 TEST(BufferCore_lookupTransform, one_link_configuration)
00960 {
00961 double epsilon = 1e-6;
00962
00963
00964
00965 rostest::Permuter permuter;
00966
00967 std::vector<ros::Time> times;
00968 times.push_back(ros::Time(1.0));
00969 times.push_back(ros::Time(10.0));
00970 times.push_back(ros::Time(0.0));
00971 ros::Time eval_time;
00972 permuter.addOptionSet(times, &eval_time);
00973
00974 std::vector<ros::Duration> durations;
00975 durations.push_back(ros::Duration(1.0));
00976 durations.push_back(ros::Duration(0.001));
00977 durations.push_back(ros::Duration(0.1));
00978 ros::Duration interpolation_space;
00979
00980
00981 std::vector<std::string> frames;
00982 frames.push_back("1");
00983 frames.push_back("2");
00984 std::string source_frame;
00985 permuter.addOptionSet(frames, &source_frame);
00986
00987 std::string target_frame;
00988 permuter.addOptionSet(frames, &target_frame);
00989
00990 while (permuter.step())
00991 {
00992
00993 tf2::BufferCore mBC;
00994 setupTree(mBC, "1", eval_time, interpolation_space);
00995
00996 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
00997
00998 EXPECT_TRUE(check_1_result(outpose, source_frame, target_frame, eval_time, epsilon));
00999 }
01000 }
01001
01002
01003 TEST(BufferCore_lookupTransform, v_configuration)
01004 {
01005 double epsilon = 1e-6;
01006
01007
01008
01009 rostest::Permuter permuter;
01010
01011 std::vector<ros::Time> times;
01012 times.push_back(ros::Time(1.0));
01013 times.push_back(ros::Time(10.0));
01014 times.push_back(ros::Time(0.0));
01015 ros::Time eval_time;
01016 permuter.addOptionSet(times, &eval_time);
01017
01018 std::vector<ros::Duration> durations;
01019 durations.push_back(ros::Duration(1.0));
01020 durations.push_back(ros::Duration(0.001));
01021 durations.push_back(ros::Duration(0.1));
01022 ros::Duration interpolation_space;
01023
01024
01025 std::vector<std::string> frames;
01026 frames.push_back("a");
01027 frames.push_back("b");
01028 frames.push_back("c");
01029 frames.push_back("f");
01030 frames.push_back("g");
01031 std::string source_frame;
01032 permuter.addOptionSet(frames, &source_frame);
01033
01034 std::string target_frame;
01035 permuter.addOptionSet(frames, &target_frame);
01036
01037 while (permuter.step())
01038 {
01039
01040 tf2::BufferCore mBC;
01041 setupTree(mBC, "v", eval_time, interpolation_space);
01042
01043 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01044
01045 EXPECT_TRUE(check_v_result(outpose, source_frame, target_frame, eval_time, epsilon));
01046 }
01047 }
01048
01049
01050 TEST(BufferCore_lookupTransform, y_configuration)
01051 {
01052 double epsilon = 1e-6;
01053
01054
01055
01056 rostest::Permuter permuter;
01057
01058 std::vector<ros::Time> times;
01059 times.push_back(ros::Time(1.0));
01060 times.push_back(ros::Time(10.0));
01061 times.push_back(ros::Time(0.0));
01062 ros::Time eval_time;
01063 permuter.addOptionSet(times, &eval_time);
01064
01065 std::vector<ros::Duration> durations;
01066 durations.push_back(ros::Duration(1.0));
01067 durations.push_back(ros::Duration(0.001));
01068 durations.push_back(ros::Duration(0.1));
01069 ros::Duration interpolation_space;
01070
01071
01072 std::vector<std::string> frames;
01073 frames.push_back("a");
01074 frames.push_back("b");
01075 frames.push_back("c");
01076 frames.push_back("d");
01077 frames.push_back("e");
01078 std::string source_frame;
01079 permuter.addOptionSet(frames, &source_frame);
01080
01081 std::string target_frame;
01082 permuter.addOptionSet(frames, &target_frame);
01083
01084 while (permuter.step())
01085 {
01086
01087 tf2::BufferCore mBC;
01088 setupTree(mBC, "y", eval_time, interpolation_space);
01089
01090 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01091
01092 EXPECT_TRUE(check_y_result(outpose, source_frame, target_frame, eval_time, epsilon));
01093 }
01094 }
01095
01096 TEST(BufferCore_lookupTransform, multi_configuration)
01097 {
01098 double epsilon = 1e-6;
01099
01100
01101
01102 rostest::Permuter permuter;
01103
01104 std::vector<ros::Time> times;
01105 times.push_back(ros::Time(1.0));
01106 times.push_back(ros::Time(10.0));
01107 times.push_back(ros::Time(0.0));
01108 ros::Time eval_time;
01109 permuter.addOptionSet(times, &eval_time);
01110
01111 std::vector<ros::Duration> durations;
01112 durations.push_back(ros::Duration(1.0));
01113 durations.push_back(ros::Duration(0.001));
01114 durations.push_back(ros::Duration(0.1));
01115 ros::Duration interpolation_space;
01116
01117
01118 std::vector<std::string> frames;
01119 frames.push_back("1");
01120 frames.push_back("2");
01121 frames.push_back("a");
01122 frames.push_back("b");
01123 frames.push_back("c");
01124 frames.push_back("f");
01125 frames.push_back("g");
01126 std::string source_frame;
01127 permuter.addOptionSet(frames, &source_frame);
01128
01129 std::string target_frame;
01130 permuter.addOptionSet(frames, &target_frame);
01131
01132 while (permuter.step())
01133 {
01134
01135 tf2::BufferCore mBC;
01136 setupTree(mBC, "1_v", eval_time, interpolation_space);
01137
01138 if (mBC.canTransform(source_frame, target_frame, eval_time))
01139 {
01140 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01141
01142 if ((source_frame == "1" || source_frame =="2") && (target_frame =="1" || target_frame == "2"))
01143 EXPECT_TRUE(check_1_result(outpose, source_frame, target_frame, eval_time, epsilon));
01144 else if ((source_frame == "a" || source_frame == "b" || source_frame == "c" || source_frame == "f" || source_frame == "g") &&
01145 (target_frame == "a" || target_frame == "b" || target_frame == "c" || target_frame == "f" || target_frame == "g"))
01146 EXPECT_TRUE(check_v_result(outpose, source_frame, target_frame, eval_time, epsilon));
01147 else
01148 EXPECT_FALSE("Frames unhandled");
01149 }
01150 else
01151 EXPECT_TRUE(((source_frame == "a" || source_frame =="b" || source_frame == "c" || source_frame == "f" || source_frame == "g") &&
01152 (target_frame == "1" || target_frame == "2") )
01153 ||
01154 ((target_frame == "a" || target_frame =="b" || target_frame == "c" || target_frame == "f" || target_frame == "g") &&
01155 (source_frame == "1" || source_frame == "2"))
01156 );
01157
01158 }
01159 }
01160
01161 #define CHECK_QUATERNION_NEAR(_q1, _x, _y, _z, _w, _epsilon) \
01162 { \
01163 btQuaternion q1(_q1.x, _q1.y, _q1.z, _q1.w); \
01164 btQuaternion q2(_x, _y, _z, _w); \
01165 double angle = q1.angle(q2); \
01166 EXPECT_TRUE(fabs(angle) < _epsilon || fabs(angle - M_PI) < _epsilon); \
01167 }
01168
01169 #define CHECK_TRANSFORMS_NEAR(_out, _expected, _eps) \
01170 EXPECT_NEAR(_out.transform.translation.x, _expected.getOrigin().x(), epsilon); \
01171 EXPECT_NEAR(_out.transform.translation.y, _expected.getOrigin().y(), epsilon); \
01172 EXPECT_NEAR(_out.transform.translation.z, _expected.getOrigin().z(), epsilon); \
01173 CHECK_QUATERNION_NEAR(_out.transform.rotation, _expected.getRotation().x(), _expected.getRotation().y(), _expected.getRotation().z(), _expected.getRotation().w(), _eps);
01174
01175
01176
01177 TEST(BufferCore_lookupTransform, compound_xfm_configuration)
01178 {
01179
01180
01181
01182
01183
01184
01185
01186
01187
01188 double epsilon = 2e-5;
01189
01190 tf2::BufferCore mBC;
01191
01192 geometry_msgs::TransformStamped tsa;
01193 tsa.header.frame_id = "root";
01194 tsa.child_frame_id = "a";
01195 tsa.transform.translation.x = 1.0;
01196 tsa.transform.translation.y = 1.0;
01197 tsa.transform.translation.z = 1.0;
01198 btQuaternion q1;
01199 q1.setRPY(0.25, .5, .75);
01200 tsa.transform.rotation.x = q1.x();
01201 tsa.transform.rotation.y = q1.y();
01202 tsa.transform.rotation.z = q1.z();
01203 tsa.transform.rotation.w = q1.w();
01204 EXPECT_TRUE(mBC.setTransform(tsa, "authority"));
01205
01206 geometry_msgs::TransformStamped tsb;
01207 tsb.header.frame_id = "root";
01208 tsb.child_frame_id = "b";
01209 tsb.transform.translation.x = -1.0;
01210 tsb.transform.translation.y = 0.0;
01211 tsb.transform.translation.z = -1.0;
01212 btQuaternion q2;
01213 q2.setRPY(1.0, 0.25, 0.5);
01214 tsb.transform.rotation.x = q2.x();
01215 tsb.transform.rotation.y = q2.y();
01216 tsb.transform.rotation.z = q2.z();
01217 tsb.transform.rotation.w = q2.w();
01218 EXPECT_TRUE(mBC.setTransform(tsb, "authority"));
01219
01220 geometry_msgs::TransformStamped tsc;
01221 tsc.header.frame_id = "b";
01222 tsc.child_frame_id = "c";
01223 tsc.transform.translation.x = 0.0;
01224 tsc.transform.translation.y = 2.0;
01225 tsc.transform.translation.z = 0.5;
01226 btQuaternion q3;
01227 q3.setRPY(0.25, .75, 1.25);
01228 tsc.transform.rotation.x = q3.x();
01229 tsc.transform.rotation.y = q3.y();
01230 tsc.transform.rotation.z = q3.z();
01231 tsc.transform.rotation.w = q3.w();
01232 EXPECT_TRUE(mBC.setTransform(tsc, "authority"));
01233
01234 geometry_msgs::TransformStamped tsd;
01235 tsd.header.frame_id = "c";
01236 tsd.child_frame_id = "d";
01237 tsd.transform.translation.x = 0.5;
01238 tsd.transform.translation.y = -1;
01239 tsd.transform.translation.z = 1.5;
01240 btQuaternion q4;
01241 q4.setRPY(-0.5, 1.0, -.75);
01242 tsd.transform.rotation.x = q4.x();
01243 tsd.transform.rotation.y = q4.y();
01244 tsd.transform.rotation.z = q4.z();
01245 tsd.transform.rotation.w = q4.w();
01246 EXPECT_TRUE(mBC.setTransform(tsd, "authority"));
01247
01248 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;
01249 ta.setOrigin(btVector3(1.0, 1.0, 1.0));
01250 ta.setRotation(q1);
01251 tb.setOrigin(btVector3(-1.0, 0.0, -1.0));
01252 tb.setRotation(q2);
01253 tc.setOrigin(btVector3(0.0, 2.0, 0.5));
01254 tc.setRotation(q3);
01255 td.setOrigin(btVector3(0.5, -1, 1.5));
01256 td.setRotation(q4);
01257
01258
01259 expected_ab = ta.inverse() * tb;
01260 expected_ac = ta.inverse() * tb * tc;
01261 expected_ad = ta.inverse() * tb * tc * td;
01262 expected_cb = tc.inverse();
01263 expected_bc = tc;
01264 expected_bd = tc * td;
01265 expected_db = expected_bd.inverse();
01266 expected_ba = tb.inverse() * ta;
01267 expected_ca = tc.inverse() * tb.inverse() * ta;
01268 expected_da = td.inverse() * tc.inverse() * tb.inverse() * ta;
01269 expected_rootd = tb * tc * td;
01270 expected_rootc = tb * tc;
01271
01272
01273 geometry_msgs::TransformStamped out_rootc = mBC.lookupTransform("root", "c", ros::Time());
01274 CHECK_TRANSFORMS_NEAR(out_rootc, expected_rootc, epsilon);
01275
01276
01277 geometry_msgs::TransformStamped out_rootd = mBC.lookupTransform("root", "d", ros::Time());
01278 CHECK_TRANSFORMS_NEAR(out_rootd, expected_rootd, epsilon);
01279
01280
01281 geometry_msgs::TransformStamped out_ab = mBC.lookupTransform("a", "b", ros::Time());
01282 CHECK_TRANSFORMS_NEAR(out_ab, expected_ab, epsilon);
01283
01284 geometry_msgs::TransformStamped out_ba = mBC.lookupTransform("b", "a", ros::Time());
01285 CHECK_TRANSFORMS_NEAR(out_ba, expected_ba, epsilon);
01286
01287
01288 geometry_msgs::TransformStamped out_ac = mBC.lookupTransform("a", "c", ros::Time());
01289 CHECK_TRANSFORMS_NEAR(out_ac, expected_ac, epsilon);
01290
01291 geometry_msgs::TransformStamped out_ca = mBC.lookupTransform("c", "a", ros::Time());
01292 CHECK_TRANSFORMS_NEAR(out_ca, expected_ca, epsilon);
01293
01294
01295 geometry_msgs::TransformStamped out_ad = mBC.lookupTransform("a", "d", ros::Time());
01296 CHECK_TRANSFORMS_NEAR(out_ad, expected_ad, epsilon);
01297
01298 geometry_msgs::TransformStamped out_da = mBC.lookupTransform("d", "a", ros::Time());
01299 CHECK_TRANSFORMS_NEAR(out_da, expected_da, epsilon);
01300
01301
01302 geometry_msgs::TransformStamped out_cb = mBC.lookupTransform("c", "b", ros::Time());
01303 CHECK_TRANSFORMS_NEAR(out_cb, expected_cb, epsilon);
01304
01305 geometry_msgs::TransformStamped out_bc = mBC.lookupTransform("b", "c", ros::Time());
01306 CHECK_TRANSFORMS_NEAR(out_bc, expected_bc, epsilon);
01307
01308
01309 geometry_msgs::TransformStamped out_bd = mBC.lookupTransform("b", "d", ros::Time());
01310 CHECK_TRANSFORMS_NEAR(out_bd, expected_bd, epsilon);
01311
01312 geometry_msgs::TransformStamped out_db = mBC.lookupTransform("d", "b", ros::Time());
01313 CHECK_TRANSFORMS_NEAR(out_db, expected_db, epsilon);
01314 }
01315
01316
01317 TEST(BufferCore_lookupTransform, helix_configuration)
01318 {
01319 double epsilon = 2e-5;
01320
01321 tf2::BufferCore mBC;
01322
01323 ros::Time t0 = ros::Time() + ros::Duration(10);
01324 ros::Duration step = ros::Duration(0.05);
01325 ros::Duration half_step = ros::Duration(0.025);
01326 ros::Time t1 = t0 + ros::Duration(5.0);
01327
01328
01329
01330
01331
01332
01333
01334
01335
01336
01337
01338
01339
01340
01341 double theta = 0.25;
01342 double vel = 1.0;
01343
01344 for (ros::Time t = t0; t <= t1; t += step)
01345 {
01346 ros::Time t2 = t + half_step;
01347 double dt = (t - t0).toSec();
01348 double dt2 = (t2 - t0).toSec();
01349
01350 geometry_msgs::TransformStamped ts;
01351 ts.header.frame_id = "a";
01352 ts.header.stamp = t;
01353 ts.child_frame_id = "b";
01354 ts.transform.translation.z = vel * dt;
01355 ts.transform.rotation.w = 1.0;
01356 EXPECT_TRUE(mBC.setTransform(ts, "authority"));
01357
01358 geometry_msgs::TransformStamped ts2;
01359 ts2.header.frame_id = "b";
01360 ts2.header.stamp = t;
01361 ts2.child_frame_id = "c";
01362 ts2.transform.translation.x = cos(theta * dt);
01363 ts2.transform.translation.y = sin(theta * dt);
01364 btQuaternion q;
01365 q.setRPY(0,0,theta*dt);
01366 ts2.transform.rotation.z = q.z();
01367 ts2.transform.rotation.w = q.w();
01368 EXPECT_TRUE(mBC.setTransform(ts2, "authority"));
01369
01370 geometry_msgs::TransformStamped ts3;
01371 ts3.header.frame_id = "a";
01372 ts3.header.stamp = t2;
01373 ts3.child_frame_id = "d";
01374 ts3.transform.translation.z = cos(theta * dt2);
01375 ts3.transform.rotation.w = 1.0;
01376 EXPECT_TRUE(mBC.setTransform(ts3, "authority"));
01377 }
01378
01379
01380 for (ros::Time t = t0 + half_step; t < t1; t += step)
01381 {
01382 ros::Time t2 = t + half_step;
01383 double dt = (t - t0).toSec();
01384 double dt2 = (t2 - t0).toSec();
01385
01386 geometry_msgs::TransformStamped out_ab = mBC.lookupTransform("a", "b", t);
01387 EXPECT_NEAR(out_ab.transform.translation.z, vel * dt, epsilon);
01388
01389 geometry_msgs::TransformStamped out_ac = mBC.lookupTransform("a", "c", t);
01390 EXPECT_NEAR(out_ac.transform.translation.x, cos(theta * dt), epsilon);
01391 EXPECT_NEAR(out_ac.transform.translation.y, sin(theta * dt), epsilon);
01392 EXPECT_NEAR(out_ac.transform.translation.z, vel * dt, epsilon);
01393 btQuaternion q;
01394 q.setRPY(0,0,theta*dt);
01395 CHECK_QUATERNION_NEAR(out_ac.transform.rotation, 0, 0, q.z(), q.w(), epsilon);
01396
01397 geometry_msgs::TransformStamped out_ad = mBC.lookupTransform("a", "d", t);
01398 EXPECT_NEAR(out_ad.transform.translation.z, cos(theta * dt), epsilon);
01399
01400 geometry_msgs::TransformStamped out_cd = mBC.lookupTransform("c", "d", t2);
01401 EXPECT_NEAR(out_cd.transform.translation.x, -1, epsilon);
01402 EXPECT_NEAR(out_cd.transform.translation.y, 0, epsilon);
01403 EXPECT_NEAR(out_cd.transform.translation.z, cos(theta * dt2) - vel * dt2, epsilon);
01404 btQuaternion mq;
01405 mq.setRPY(0,0,-theta*dt2);
01406 CHECK_QUATERNION_NEAR(out_cd.transform.rotation, 0, 0, mq.z(), mq.w(), epsilon);
01407 }
01408
01409
01410 for (ros::Time t = t0 + half_step; t < t1; t += (step + step))
01411 {
01412 ros::Time t2 = t + step;
01413 double dt = (t - t0).toSec();
01414 double dt2 = (t2 - t0).toSec();
01415
01416 geometry_msgs::TransformStamped out_cd2 = mBC.lookupTransform("c", t, "d", t2, "a");
01417 EXPECT_NEAR(out_cd2.transform.translation.x, -1, epsilon);
01418 EXPECT_NEAR(out_cd2.transform.translation.y, 0, epsilon);
01419 EXPECT_NEAR(out_cd2.transform.translation.z, cos(theta * dt2) - vel * dt, epsilon);
01420 btQuaternion mq2;
01421 mq2.setRPY(0,0,-theta*dt);
01422 CHECK_QUATERNION_NEAR(out_cd2.transform.rotation, 0, 0, mq2.z(), mq2.w(), epsilon);
01423 }
01424 }
01425
01426
01427 TEST(BufferCore_lookupTransform, ring_45_configuration)
01428 {
01429 double epsilon = 1e-6;
01430 rostest::Permuter permuter;
01431
01432 std::vector<ros::Time> times;
01433 times.push_back(ros::Time(1.0));
01434 times.push_back(ros::Time(10.0));
01435 times.push_back(ros::Time(0.0));
01436 ros::Time eval_time;
01437 permuter.addOptionSet(times, &eval_time);
01438
01439 std::vector<ros::Duration> durations;
01440 durations.push_back(ros::Duration(1.0));
01441 durations.push_back(ros::Duration(0.001));
01442 durations.push_back(ros::Duration(0.1));
01443 ros::Duration interpolation_space;
01444
01445
01446 std::vector<std::string> frames;
01447 frames.push_back("a");
01448 frames.push_back("b");
01449 frames.push_back("c");
01450 frames.push_back("d");
01451 frames.push_back("e");
01452 frames.push_back("f");
01453 frames.push_back("g");
01454 frames.push_back("h");
01455 frames.push_back("i");
01456
01457
01458
01459
01460
01461
01462
01463
01464 std::string source_frame;
01465 permuter.addOptionSet(frames, &source_frame);
01466
01467 std::string target_frame;
01468 permuter.addOptionSet(frames, &target_frame);
01469
01470 while (permuter.step())
01471 {
01472
01473 tf2::BufferCore mBC;
01474 setupTree(mBC, "ring_45", eval_time, interpolation_space);
01475
01476 geometry_msgs::TransformStamped outpose = mBC.lookupTransform(source_frame, target_frame, eval_time);
01477
01478
01479
01480 EXPECT_EQ(outpose.header.stamp, eval_time);
01481 EXPECT_EQ(outpose.header.frame_id, source_frame);
01482 EXPECT_EQ(outpose.child_frame_id, target_frame);
01483
01484
01485
01486
01487 if (source_frame == target_frame ||
01488 (source_frame == "a" && target_frame == "i") ||
01489 (source_frame == "i" && target_frame == "a") ||
01490 (source_frame == "a" && target_frame == "inverse_i") ||
01491 (source_frame == "inverse_i" && target_frame == "a") )
01492 {
01493
01494 EXPECT_NEAR(outpose.transform.translation.x, 0, epsilon);
01495 EXPECT_NEAR(outpose.transform.translation.y, 0, epsilon);
01496 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01497 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01498 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01499 EXPECT_NEAR(outpose.transform.rotation.z, 0, epsilon);
01500 EXPECT_NEAR(fabs(outpose.transform.rotation.w), 1, epsilon);
01501 }
01502
01503 else if ((source_frame == "a" && target_frame =="b") ||
01504 (source_frame == "b" && target_frame =="c") ||
01505 (source_frame == "c" && target_frame =="d") ||
01506 (source_frame == "d" && target_frame =="e") ||
01507 (source_frame == "e" && target_frame =="f") ||
01508 (source_frame == "f" && target_frame =="g") ||
01509 (source_frame == "g" && target_frame =="h") ||
01510 (source_frame == "h" && target_frame =="i")
01511 )
01512 {
01513 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01514 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01515 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01516 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01517 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01518 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI/8), epsilon);
01519 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI/8), epsilon);
01520 }
01521
01522 else if ((source_frame == "b" && target_frame =="a") ||
01523 (source_frame == "c" && target_frame =="b") ||
01524 (source_frame == "d" && target_frame =="c") ||
01525 (source_frame == "e" && target_frame =="d") ||
01526 (source_frame == "f" && target_frame =="e") ||
01527 (source_frame == "g" && target_frame =="f") ||
01528 (source_frame == "h" && target_frame =="g") ||
01529 (source_frame == "i" && target_frame =="h")
01530 )
01531 {
01532 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01533 EXPECT_NEAR(outpose.transform.translation.y, -sqrt(2)/2 , epsilon);
01534 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01535 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01536 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01537 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI/8), epsilon);
01538 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI/8), epsilon);
01539 }
01540
01541 else if ((source_frame == "a" && target_frame =="c") ||
01542 (source_frame == "b" && target_frame =="d") ||
01543 (source_frame == "c" && target_frame =="e") ||
01544 (source_frame == "d" && target_frame =="f") ||
01545 (source_frame == "e" && target_frame =="g") ||
01546 (source_frame == "f" && target_frame =="h") ||
01547 (source_frame == "g" && target_frame =="i")
01548 )
01549 {
01550 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01551 EXPECT_NEAR(outpose.transform.translation.y, 1 , epsilon);
01552 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01553 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01554 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01555 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI/4), epsilon);
01556 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI/4), epsilon);
01557 }
01558
01559 else if ((source_frame == "c" && target_frame =="a") ||
01560 (source_frame == "d" && target_frame =="b") ||
01561 (source_frame == "e" && target_frame =="c") ||
01562 (source_frame == "f" && target_frame =="d") ||
01563 (source_frame == "g" && target_frame =="e") ||
01564 (source_frame == "h" && target_frame =="f") ||
01565 (source_frame == "i" && target_frame =="g")
01566 )
01567 {
01568 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01569 EXPECT_NEAR(outpose.transform.translation.y, -1 , epsilon);
01570 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01571 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01572 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01573 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI/4), epsilon);
01574 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI/4), epsilon);
01575 }
01576
01577 else if ((source_frame == "a" && target_frame =="d") ||
01578 (source_frame == "b" && target_frame =="e") ||
01579 (source_frame == "c" && target_frame =="f") ||
01580 (source_frame == "d" && target_frame =="g") ||
01581 (source_frame == "e" && target_frame =="h") ||
01582 (source_frame == "f" && target_frame =="i")
01583 )
01584 {
01585 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2)/2, epsilon);
01586 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01587 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01588 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01589 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01590 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*3/8), epsilon);
01591 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*3/8), epsilon);
01592 }
01593
01594 else if ((target_frame == "a" && source_frame =="d") ||
01595 (target_frame == "b" && source_frame =="e") ||
01596 (target_frame == "c" && source_frame =="f") ||
01597 (target_frame == "d" && source_frame =="g") ||
01598 (target_frame == "e" && source_frame =="h") ||
01599 (target_frame == "f" && source_frame =="i")
01600 )
01601 {
01602 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2)/2, epsilon);
01603 EXPECT_NEAR(outpose.transform.translation.y, - sqrt(2)/2 , epsilon);
01604 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01605 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01606 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01607 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*3/8), epsilon);
01608 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*3/8), epsilon);
01609 }
01610
01611 else if ((source_frame == "a" && target_frame =="e") ||
01612 (source_frame == "b" && target_frame =="f") ||
01613 (source_frame == "c" && target_frame =="g") ||
01614 (source_frame == "d" && target_frame =="h") ||
01615 (source_frame == "e" && target_frame =="i")
01616 )
01617 {
01618 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
01619 EXPECT_NEAR(outpose.transform.translation.y, 0 , epsilon);
01620 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01621 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01622 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01623 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI/2), epsilon);
01624 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI/2), epsilon);
01625 }
01626
01627 else if ((target_frame == "a" && source_frame =="e") ||
01628 (target_frame == "b" && source_frame =="f") ||
01629 (target_frame == "c" && source_frame =="g") ||
01630 (target_frame == "d" && source_frame =="h") ||
01631 (target_frame == "e" && source_frame =="i")
01632 )
01633 {
01634 EXPECT_NEAR(outpose.transform.translation.x, -2, epsilon);
01635 EXPECT_NEAR(outpose.transform.translation.y, 0 , epsilon);
01636 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01637 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01638 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01639 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI/2), epsilon);
01640 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI/2), epsilon);
01641 }
01642
01643 else if ((source_frame == "a" && target_frame =="f") ||
01644 (source_frame == "b" && target_frame =="g") ||
01645 (source_frame == "c" && target_frame =="h") ||
01646 (source_frame == "d" && target_frame =="i")
01647 )
01648 {
01649 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2) /2, epsilon);
01650 EXPECT_NEAR(outpose.transform.translation.y, - sqrt(2) /2 , epsilon);
01651 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01652 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01653 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01654 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*5/8), epsilon);
01655 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*5/8), epsilon);
01656 }
01657
01658 else if ((target_frame == "a" && source_frame =="f") ||
01659 (target_frame == "b" && source_frame =="g") ||
01660 (target_frame == "c" && source_frame =="h") ||
01661 (target_frame == "d" && source_frame =="i")
01662 )
01663 {
01664 EXPECT_NEAR(outpose.transform.translation.x, -1 - sqrt(2)/2, epsilon);
01665 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01666 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01667 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01668 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01669 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*5/8), epsilon);
01670 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*5/8), epsilon);
01671 }
01672
01673 else if ((source_frame == "a" && target_frame =="g") ||
01674 (source_frame == "b" && target_frame =="h") ||
01675 (source_frame == "c" && target_frame =="i")
01676 )
01677 {
01678 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01679 EXPECT_NEAR(outpose.transform.translation.y, -1 , epsilon);
01680 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01681 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01682 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01683 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*6/8), epsilon);
01684 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*6/8), epsilon);
01685 }
01686
01687 else if ((target_frame == "a" && source_frame =="g") ||
01688 (target_frame == "b" && source_frame =="h") ||
01689 (target_frame == "c" && source_frame =="i")
01690 )
01691 {
01692 EXPECT_NEAR(outpose.transform.translation.x, -1, epsilon);
01693 EXPECT_NEAR(outpose.transform.translation.y, 1 , epsilon);
01694 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01695 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01696 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01697 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*6/8), epsilon);
01698 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*6/8), epsilon);
01699 }
01700
01701 else if ((source_frame == "a" && target_frame =="h") ||
01702 (source_frame == "b" && target_frame =="i")
01703 )
01704 {
01705 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01706 EXPECT_NEAR(outpose.transform.translation.y, -sqrt(2)/2 , epsilon);
01707 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01708 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01709 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01710 EXPECT_NEAR(outpose.transform.rotation.z, sin(M_PI*7/8), epsilon);
01711 EXPECT_NEAR(outpose.transform.rotation.w, cos(M_PI*7/8), epsilon);
01712 }
01713
01714 else if ((target_frame == "a" && source_frame =="h") ||
01715 (target_frame == "b" && source_frame =="i")
01716 )
01717 {
01718 EXPECT_NEAR(outpose.transform.translation.x, sqrt(2)/2 - 1, epsilon);
01719 EXPECT_NEAR(outpose.transform.translation.y, sqrt(2)/2 , epsilon);
01720 EXPECT_NEAR(outpose.transform.translation.z, 0, epsilon);
01721 EXPECT_NEAR(outpose.transform.rotation.x, 0, epsilon);
01722 EXPECT_NEAR(outpose.transform.rotation.y, 0, epsilon);
01723 EXPECT_NEAR(outpose.transform.rotation.z, sin(-M_PI*7/8), epsilon);
01724 EXPECT_NEAR(outpose.transform.rotation.w, cos(-M_PI*7/8), epsilon);
01725 }
01726 else
01727 {
01728 EXPECT_FALSE("Ring_45 testing Shouldn't get here");
01729 printf("source_frame %s target_frame %s time %f\n", source_frame.c_str(), target_frame.c_str(), eval_time.toSec());
01730 }
01731
01732 }
01733 }
01734
01735 TEST(BufferCore_lookupTransform, invalid_arguments)
01736 {
01737 tf2::BufferCore mBC;
01738
01739 setupTree(mBC, "i", ros::Time(1.0));
01740
01741 EXPECT_NO_THROW(mBC.lookupTransform("b", "a", ros::Time()));
01742
01743
01744 EXPECT_THROW(mBC.lookupTransform("", "a", ros::Time()), tf2::InvalidArgumentException);
01745 EXPECT_THROW(mBC.lookupTransform("b", "", ros::Time()), tf2::InvalidArgumentException);
01746
01747
01748 EXPECT_THROW(mBC.lookupTransform("/b", "a", ros::Time()), tf2::InvalidArgumentException);
01749 EXPECT_THROW(mBC.lookupTransform("b", "/a", ros::Time()), tf2::InvalidArgumentException);
01750
01751 };
01752
01753 TEST(BufferCore_canTransform, invalid_arguments)
01754 {
01755 tf2::BufferCore mBC;
01756
01757 setupTree(mBC, "i", ros::Time(1.0));
01758
01759 EXPECT_TRUE(mBC.canTransform("b", "a", ros::Time()));
01760
01761
01762
01763 EXPECT_FALSE(mBC.canTransform("", "a", ros::Time()));
01764 EXPECT_FALSE(mBC.canTransform("b", "", ros::Time()));
01765
01766
01767 EXPECT_FALSE(mBC.canTransform("/b", "a", ros::Time()));
01768 EXPECT_FALSE(mBC.canTransform("b", "/a", ros::Time()));
01769
01770 };
01771
01772 struct TransformableHelper
01773 {
01774 TransformableHelper()
01775 : called(false)
01776 {}
01777
01778 void callback(tf2::TransformableRequestHandle request_handle, const std::string& target_frame, const std::string& source_frame,
01779 ros::Time time, tf2::TransformableResult result)
01780 {
01781 called = true;
01782 }
01783
01784 bool called;
01785 };
01786
01787 TEST(BufferCore_transformableCallbacks, alreadyTransformable)
01788 {
01789 tf2::BufferCore b;
01790 TransformableHelper h;
01791
01792 geometry_msgs::TransformStamped t;
01793 t.header.stamp = ros::Time(1);
01794 t.header.frame_id = "a";
01795 t.child_frame_id = "b";
01796 t.transform.rotation.w = 1.0;
01797 b.setTransform(t, "me");
01798
01799 tf2::TransformableCallbackHandle cb_handle = b.addTransformableCallback(boost::bind(&TransformableHelper::callback, &h, _1, _2, _3, _4, _5));
01800 EXPECT_EQ(b.addTransformableRequest(cb_handle, "a", "b", ros::Time(1)), 0U);
01801 }
01802
01803 TEST(BufferCore_transformableCallbacks, waitForNewTransform)
01804 {
01805 tf2::BufferCore b;
01806 TransformableHelper h;
01807 tf2::TransformableCallbackHandle cb_handle = b.addTransformableCallback(boost::bind(&TransformableHelper::callback, &h, _1, _2, _3, _4, _5));
01808 EXPECT_GT(b.addTransformableRequest(cb_handle, "a", "b", ros::Time(10)), 0U);
01809
01810 geometry_msgs::TransformStamped t;
01811 for (uint32_t i = 1; i <= 10; ++i)
01812 {
01813 t.header.stamp = ros::Time(i);
01814 t.header.frame_id = "a";
01815 t.child_frame_id = "b";
01816 t.transform.rotation.w = 1.0;
01817 b.setTransform(t, "me");
01818
01819 if (i < 10)
01820 {
01821 ASSERT_FALSE(h.called);
01822 }
01823 else
01824 {
01825 ASSERT_TRUE(h.called);
01826 }
01827 }
01828 }
01829
01830 TEST(BufferCore_transformableCallbacks, waitForOldTransform)
01831 {
01832 tf2::BufferCore b;
01833 TransformableHelper h;
01834 tf2::TransformableCallbackHandle cb_handle = b.addTransformableCallback(boost::bind(&TransformableHelper::callback, &h, _1, _2, _3, _4, _5));
01835 EXPECT_GT(b.addTransformableRequest(cb_handle, "a", "b", ros::Time(1)), 0U);
01836
01837 geometry_msgs::TransformStamped t;
01838 for (uint32_t i = 10; i > 0; --i)
01839 {
01840 t.header.stamp = ros::Time(i);
01841 t.header.frame_id = "a";
01842 t.child_frame_id = "b";
01843 t.transform.rotation.w = 1.0;
01844 b.setTransform(t, "me");
01845
01846 if (i > 1)
01847 {
01848 ASSERT_FALSE(h.called);
01849 }
01850 else
01851 {
01852 ASSERT_TRUE(h.called);
01853 }
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 int main(int argc, char **argv){
02812 testing::InitGoogleTest(&argc, argv);
02813 ros::Time::init();
02814 ros::init(argc, argv, "tf_unittest");
02815 return RUN_ALL_TESTS();
02816 }