13 #include <gtest/gtest.h> 34 CPose3D p1(0,0,0, YAW,PITCH,ROLL);
41 EXPECT_NEAR(0, std::abs((
CPose3D(q1,0,0,0).getAsVectorVal()-
CPose3D(q1r,0,0,0).getAsVectorVal()).
sum()), 1e-6);
46 CPose3D p1(0,0,0, YAW,PITCH,ROLL);
51 "ypr->quat->ypr failed with:" << endl
52 <<
" p1:" << p1 << endl
53 <<
" q1:" << q1 << endl
54 <<
" p2:" << p2 << endl;
57 EXPECT_NEAR(0,(p1.
getRotationMatrix()-p3.getRotationMatrix()).array().abs().sum(), 1e-4) <<
58 "pose constructor from quat failed with:" << endl
59 <<
" p1:" << p1 << endl
60 <<
" q1:" << q1 << endl
61 <<
" p3:" << p3 << endl;
66 const CPose3D pp(0,0,0,yaw1,pitch1,roll1);
74 EXPECT_NEAR(0, (q1-q2).array().abs().
sum(), 1e-10 )
75 <<
"q1:\n" << q1 << endl
76 <<
"q2:\n" << q2 << endl
77 <<
"Error:\n" << (q1-q2) << endl;
91 EXPECT_NEAR(0, (q1_ln-
v).array().abs().
sum(), 1e-10 )
92 <<
"v:\n" <<
v << endl
93 <<
"q1_ln:\n" << q1_ln << endl
94 <<
"Error:\n" << (q1_ln-
v) << endl;
115 "q1 = " << q1 << endl <<
116 "q1 as CPose3D = " <<
CPose3D(q1,0,0,0) << endl <<
117 "q2 = " << q2 << endl <<
118 "q2 as CPose3D = " <<
CPose3D(q2,0,0,0) << endl <<
119 "q3 = q1 * q2 = " << q3 << endl <<
120 "q3 as CPose3D = " <<
CPose3D(q3,0,0,0) << endl <<
121 "Should be equal to p3 = p1 (+) p2 = " << p3 << endl;
144 const double list_test_YPR_angles_degrees[][3] = {
146 { -1, 0, 0 }, { 1, 0, 0 },
147 { 0,-1, 0 }, { 0, 1, 0 },
148 { 0, 0, -1}, { 0, 0, 1},
149 { 40, 0, 0 }, { 0, 40, 0 }, { 0, 0, 40 },
150 { -40, 0, 0 }, { 0,-40, 0 }, { 0, 0,-40 },
151 { -30, 20, 50 }, { -30, 20,-50 }, { 30,-20,-50 }
154 const size_t N =
sizeof(list_test_YPR_angles_degrees)/
sizeof(list_test_YPR_angles_degrees[0]);
155 for (
size_t i=0;i<N;i++)
156 test_lnAndExpMatches(
DEG2RAD(list_test_YPR_angles_degrees[i][0]),
DEG2RAD(list_test_YPR_angles_degrees[i][1]),
DEG2RAD(list_test_YPR_angles_degrees[i][2]));
161 const double list_test_XYZ[][3] = {
163 { -1, 0, 0 }, { 1, 0, 0 },
164 { 0,-1, 0 }, { 0, 1, 0 },
165 { 0, 0, -1}, { 0, 0, 1},
166 { 1e-3, 0, 0}, { 0, 1e-3, 0}, {0,0, 1e-3},
167 { -1e-3, 0, 0}, { 0,-1e-3, 0}, {0,0,-1e-3},
168 { -0.1,0.2,0.3 },{-0.1,-0.2,0.3 },{-0.1,-0.2,-0.3 },{-0.1,0.2,-0.3 },{0.1,0.2,-0.3 },{0.1,0.2,0.3}
171 const size_t N =
sizeof(list_test_XYZ)/
sizeof(list_test_XYZ[0]);
172 for (
size_t i=0;i<N;i++)
173 test_ExpAndLnMatches(list_test_XYZ[i][0],list_test_XYZ[i][1],list_test_XYZ[i][2]);
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
void test_gimbalLock(double YAW, double PITCH, double ROLL)
mrpt::math::CVectorDouble getAsVectorVal() const
Return the pose or point as a 1xN vector with all the components (see derived classes for each implem...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
This base provides a set of functions for maths stuff.
void crossProduct(const CQuaternion &q1, const CQuaternion &q2)
Calculate the "cross" product (or "composed rotation") of two quaternion: this = q1 x q2 After the op...
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
void test_lnAndExpMatches(double yaw1, double pitch1, double roll1)
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void test_ExpAndLnMatches(double v0, double v1, double v2)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void ln(ARRAYLIKE3 &out_ln) const
Logarithm of the 3x3 matrix defined by this pose, generating the corresponding vector in the SO(3) Li...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
GLfloat GLfloat GLfloat v2
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
void test_toYPRAndBack(double YAW, double PITCH, double ROLL)
void getAsQuaternion(mrpt::math::CQuaternionDouble &q, mrpt::math::CMatrixFixedNumeric< double, 4, 3 > *out_dq_dr=NULL) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored) ...
TEST_F(QuaternionTests, crossProduct)