quaternion.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <vector>
31 #include <cstdio>
32 #include <ctime>
33 #include <cstdlib>
34 #include <gtest/gtest.h>
35 
37 
38 double epsilon = 10E-6;
39 
40 
41 void seed_rand()
42 {
43  //Seed random number generator with current microseond count
44  std::srand(std::time(0));
45 }
46 
47 void testQuatRPY(tf::Quaternion q_baseline)
48 {
49  q_baseline.normalize();
50  tf::Matrix3x3 m(q_baseline);
51  double roll, pitch, yaw;
52 
53  for (int solution = 1 ; solution < 2 ; ++solution)
54  {
55  m.getRPY(roll, pitch, yaw, solution);
56  tf::Quaternion q_from_rpy;
57  q_from_rpy.setRPY(roll, pitch, yaw);
58  // use angleShortestPath() because angle() can return PI for equivalent
59  // quaternions
60  double angle1 = q_from_rpy.angleShortestPath(q_baseline);
61  ASSERT_NEAR(0.0, angle1, epsilon);
62  //std::printf("%f, angle between quaternions\n", angle1);
63 
64  tf::Matrix3x3 m2;
65  m2.setRPY(roll, pitch, yaw);
66  tf::Quaternion q_from_m_from_rpy;
67  m2.getRotation(q_from_m_from_rpy);
68  // use angleShortestPath() because angle() can return PI for equivalent
69  // quaternions
70  double angle2 = q_from_m_from_rpy.angleShortestPath(q_baseline);
71  ASSERT_NEAR(0.0, angle2, epsilon);
72  //std::printf("%f, angle between quaternions\n", angle2);
73  }
74 }
75 
76 TEST(tf, Quaternion)
77 {
78  unsigned int runs = 400;
79  seed_rand();
80 
81  std::vector<double> xvalues(runs), yvalues(runs), zvalues(runs);
82  for ( unsigned int i = 0; i < runs ; i++ )
83  {
84  xvalues[i] = 1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
85  yvalues[i] = 1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
86  zvalues[i] = 1.0 * ((double) std::rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
87  }
88 
89 
90  for ( unsigned int i = 0; i < runs ; i++ )
91  {
92  tf::Matrix3x3 mat;
93  tf::Quaternion q_baseline;
94  q_baseline.setRPY(zvalues[i],yvalues[i],xvalues[i]);
95  mat.setRotation(q_baseline);
96  tf::Quaternion q_from_m;
97  mat.getRotation(q_from_m);
98  double angle = q_from_m.angle(q_baseline);
99  ASSERT_NEAR(0.0, angle, epsilon);
100  testQuatRPY(q_baseline);
101  }
102 
103  // test some corner cases
104  testQuatRPY(tf::Quaternion( 0.5, 0.5, 0.5, -0.5));
105  testQuatRPY(tf::Quaternion( 0.5, 0.5, 0.5, 0.5));
106  testQuatRPY(tf::Quaternion( 0.5, -0.5, 0.5, 0.5));
107  testQuatRPY(tf::Quaternion( 0.5, 0.5, -0.5, 0.5));
108  testQuatRPY(tf::Quaternion(-0.5, 0.5, 0.5, 0.5));
109 }
110 
111 
112 int main(int argc, char **argv){
113  testing::InitGoogleTest(&argc, argv);
114  return RUN_ALL_TESTS();
115 }
double epsilon
Definition: quaternion.cpp:38
void getRotation(Quaternion &q) const
Get the matrix represented as a quaternion.
Definition: Matrix3x3.h:245
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
void seed_rand()
Definition: quaternion.cpp:41
TEST(tf, Quaternion)
Definition: quaternion.cpp:76
tfScalar angle(const Quaternion &q) const
Return the half angle between this quaternion and the other.
Definition: Quaternion.h:213
Quaternion & normalize()
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
Definition: Quaternion.h:176
Definition: exceptions.h:38
The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Q...
Definition: Matrix3x3.h:33
void setRotation(const Quaternion &q)
Set the matrix from a quaternion.
Definition: Matrix3x3.h:148
int main(int argc, char **argv)
Definition: quaternion.cpp:112
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
Set the quaternion using fixed axis RPY.
Definition: Quaternion.h:96
void setRPY(tfScalar roll, tfScalar pitch, tfScalar yaw)
Set the matrix using RPY about XYZ fixed axes.
Definition: Matrix3x3.h:205
void testQuatRPY(tf::Quaternion q_baseline)
Definition: quaternion.cpp:47
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
Get the matrix represented as roll pitch and yaw about fixed axes XYZ.
Definition: Matrix3x3.h:367
tfScalar angleShortestPath(const Quaternion &q) const
Return the angle between this quaternion and the other along the shortest path.
Definition: Quaternion.h:221


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Feb 28 2022 22:26:19