quaternion.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <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   //Seed random number generator with current microseond count
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     // use angleShortestPath() because angle() can return PI for equivalent
00060     // quaternions
00061     double angle1 = q_from_rpy.angleShortestPath(q_baseline);
00062     ASSERT_NEAR(0.0, angle1, epsilon);
00063     //std::printf("%f, angle between quaternions\n", angle1);
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     // use angleShortestPath() because angle() can return PI for equivalent
00070     // quaternions
00071     double angle2 = q_from_m_from_rpy.angleShortestPath(q_baseline);
00072     ASSERT_NEAR(0.0, angle2, epsilon);
00073     //std::printf("%f, angle between quaternions\n", angle2);
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   // test some corner cases
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 }


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 27 2015 13:02:09