Go to the documentation of this file.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 <sys/time.h>
00033 #include <ros/ros.h>
00034 #include "tf2/LinearMath/Vector3.h"
00035 #include "tf2/exceptions.h"
00036
00037 void seed_rand()
00038 {
00039
00040 timeval temp_time_struct;
00041 gettimeofday(&temp_time_struct,NULL);
00042 srand(temp_time_struct.tv_usec);
00043 };
00044
00045 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
00046 {
00047 seed_rand();
00048 for ( uint64_t i = 0; i < runs ; i++ )
00049 {
00050 xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00051 yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00052 zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00053 }
00054 }
00055
00056
00057
00058 TEST(tf2, setTransformFail)
00059 {
00060 tf2::BufferCore tfc;
00061 geometry_msgs::TransformStamped st;
00062 EXPECT_FALSE(tfc.setTransform(st, "authority1"));
00063
00064 }
00065
00066 TEST(tf2, setTransformValid)
00067 {
00068 tf2::BufferCore tfc;
00069 geometry_msgs::TransformStamped st;
00070 st.header.frame_id = "foo";
00071 st.header.stamp = ros::Time(1.0);
00072 st.child_frame_id = "child";
00073 st.transform.rotation.w = 1;
00074 EXPECT_TRUE(tfc.setTransform(st, "authority1"));
00075
00076 }
00077
00078 TEST(tf2_lookupTransform, LookupException_Nothing_Exists)
00079 {
00080 tf2::BufferCore tfc;
00081 EXPECT_THROW(tfc.lookupTransform("a", "b", ros::Time().fromSec(1.0)), tf2::LookupException);
00082
00083 }
00084
00085 TEST(tf2_canTransform, Nothing_Exists)
00086 {
00087 tf2::BufferCore tfc;
00088 EXPECT_FALSE(tfc.canTransform("a", "b", ros::Time().fromSec(1.0)));
00089
00090 }
00091
00092 TEST(tf2_lookupTransform, LookupException_One_Exists)
00093 {
00094 tf2::BufferCore tfc;
00095 geometry_msgs::TransformStamped st;
00096 st.header.frame_id = "foo";
00097 st.header.stamp = ros::Time(1.0);
00098 st.child_frame_id = "child";
00099 st.transform.rotation.w = 1;
00100 EXPECT_TRUE(tfc.setTransform(st, "authority1"));
00101 EXPECT_THROW(tfc.lookupTransform("foo", "bar", ros::Time().fromSec(1.0)), tf2::LookupException);
00102
00103 }
00104
00105 TEST(tf2_canTransform, One_Exists)
00106 {
00107 tf2::BufferCore tfc;
00108 geometry_msgs::TransformStamped st;
00109 st.header.frame_id = "foo";
00110 st.header.stamp = ros::Time(1.0);
00111 st.child_frame_id = "child";
00112 st.transform.rotation.w = 1;
00113 EXPECT_TRUE(tfc.setTransform(st, "authority1"));
00114 EXPECT_FALSE(tfc.canTransform("foo", "bar", ros::Time().fromSec(1.0)));
00115 }
00116
00117
00118 int main(int argc, char **argv){
00119 testing::InitGoogleTest(&argc, argv);
00120 ros::Time::init();
00121 return RUN_ALL_TESTS();
00122 }