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 <vector>
00031 #include <sys/time.h>
00032 #include <cstdio>
00033 #include <gtest/gtest.h>
00034
00035 #include "tf/LinearMath/Transform.h"
00036
00037 double epsilon = 10E-6;
00038
00039
00040 void seed_rand()
00041 {
00042
00043 timeval temp_time_struct;
00044 gettimeofday(&temp_time_struct,NULL);
00045 srand(temp_time_struct.tv_usec);
00046 };
00047
00048 void testQuatRPY(tf::Quaternion q_baseline)
00049 {
00050 q_baseline.normalize();
00051 tf::Matrix3x3 m(q_baseline);
00052 double roll, pitch, yaw;
00053
00054 for (int solution = 1 ; solution < 2 ; ++solution)
00055 {
00056 m.getRPY(roll, pitch, yaw, solution);
00057 tf::Quaternion q_from_rpy;
00058 q_from_rpy.setRPY(roll, pitch, yaw);
00059
00060
00061 double angle1 = q_from_rpy.angleShortestPath(q_baseline);
00062 ASSERT_NEAR(0.0, angle1, epsilon);
00063
00064
00065 tf::Matrix3x3 m2;
00066 m2.setRPY(roll, pitch, yaw);
00067 tf::Quaternion q_from_m_from_rpy;
00068 m2.getRotation(q_from_m_from_rpy);
00069
00070
00071 double angle2 = q_from_m_from_rpy.angleShortestPath(q_baseline);
00072 ASSERT_NEAR(0.0, angle2, epsilon);
00073
00074 }
00075 }
00076
00077 TEST(tf, Quaternion)
00078 {
00079 unsigned int runs = 400;
00080 seed_rand();
00081
00082 std::vector<double> xvalues(runs), yvalues(runs), zvalues(runs);
00083 for ( unsigned int i = 0; i < runs ; i++ )
00084 {
00085 xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00086 yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00087 zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00088 }
00089
00090
00091 for ( unsigned int i = 0; i < runs ; i++ )
00092 {
00093 tf::Matrix3x3 mat;
00094 tf::Quaternion q_baseline;
00095 q_baseline.setRPY(zvalues[i],yvalues[i],xvalues[i]);
00096 mat.setRotation(q_baseline);
00097 tf::Quaternion q_from_m;
00098 mat.getRotation(q_from_m);
00099 double angle = q_from_m.angle(q_baseline);
00100 ASSERT_NEAR(0.0, angle, epsilon);
00101 testQuatRPY(q_baseline);
00102 }
00103
00104
00105 testQuatRPY(tf::Quaternion( 0.5, 0.5, 0.5, -0.5));
00106 testQuatRPY(tf::Quaternion( 0.5, 0.5, 0.5, 0.5));
00107 testQuatRPY(tf::Quaternion( 0.5, -0.5, 0.5, 0.5));
00108 testQuatRPY(tf::Quaternion( 0.5, 0.5, -0.5, 0.5));
00109 testQuatRPY(tf::Quaternion(-0.5, 0.5, 0.5, 0.5));
00110 }
00111
00112
00113 int main(int argc, char **argv){
00114 testing::InitGoogleTest(&argc, argv);
00115 return RUN_ALL_TESTS();
00116 }