Main MRPT website > C++ reference for MRPT 1.4.0
CQuaternion.h
Go to the documentation of this file.
1/* +---------------------------------------------------------------------------+
2 | Mobile Robot Programming Toolkit (MRPT) |
3 | http://www.mrpt.org/ |
4 | |
5 | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6 | See: http://www.mrpt.org/Authors - All rights reserved. |
7 | Released under BSD License. See details in http://www.mrpt.org/License |
8 +---------------------------------------------------------------------------+ */
9
10#ifndef CQuaternion_H
11#define CQuaternion_H
12
15
16namespace mrpt
17{
18 namespace math
19 {
20 // For use with a constructor of CQuaternion
22 {
24 };
25
26 /** A quaternion, which can represent a 3D rotation as pair \f$ (r,\mathbf{u}) \f$, with a real part "r" and a 3D vector \f$ \mathbf{u} = (x,y,z) \f$, or alternatively, q = r + ix + jy + kz.
27 *
28 * The elements of the quaternion can be accessed by either:
29 * - r(), x(), y(), z(), or
30 * - the operator [] with indices running from 0 (=r) to 3 (=z).
31 *
32 * Users will usually employ the typedef "CQuaternionDouble" instead of this template.
33 *
34 * For more information about quaternions, see:
35 * - http://people.csail.mit.edu/bkph/articles/Quaternions.pdf
36 * - http://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
37 *
38 * \ingroup mrpt_base_grp
39 * \sa mrpt::poses::CPose3D
40 */
41 template <class T>
42 class CQuaternion : public CArrayNumeric<T,4>
43 {
45 public:
46 /* @{ Constructors
47 */
48
49 /** Can be used with UNINITIALIZED_QUATERNION as argument, does not initialize the 4 elements of the quaternion (use this constructor when speed is critical). */
51
52 /** Default constructor: construct a (1, (0,0,0) ) quaternion representing no rotation. */
53 inline CQuaternion()
54 {
55 (*this)[0] = 1;
56 (*this)[1] = 0;
57 (*this)[2] = 0;
58 (*this)[3] = 0;
59 }
60
61 /** Construct a quaternion from its parameters 'r', 'x', 'y', 'z', with q = r + ix + jy + kz. */
62 inline CQuaternion(const T r,const T x,const T y,const T z)
63 {
64 (*this)[0] = r;
65 (*this)[1] = x;
66 (*this)[2] = y;
67 (*this)[3] = z;
68 ASSERTMSG_(std::abs(normSqr()-1.0)<1e-5, mrpt::format("Initialization data for quaternion is not normalized: %f %f %f %f -> sqrNorm=%f",r,x,y,z,normSqr()) );
69 }
70
71 /* @}
72 */
73
74
75 inline T r()const {return (*this)[0];} //!< Return r coordinate of the quaternion
76 inline T x()const {return (*this)[1];} //!< Return x coordinate of the quaternion
77 inline T y()const {return (*this)[2];} //!< Return y coordinate of the quaternion
78 inline T z()const {return (*this)[3];} //!< Return z coordinate of the quaternion
79 inline void r(const T r) {(*this)[0]=r;} //!< Set r coordinate of the quaternion
80 inline void x(const T x) {(*this)[1]=x;} //!< Set x coordinate of the quaternion
81 inline void y(const T y) {(*this)[2]=y;} //!< Set y coordinate of the quaternion
82 inline void z(const T z) {(*this)[3]=z;} //!< Set z coordinate of the quaternion
83
84 /** Set this quaternion to the rotation described by a 3D (Rodrigues) rotation vector \f$ \mathbf{v} \f$:
85 * If \f$ \mathbf{v}=0 \f$, then the quaternion is \f$ \mathbf{q} = [1 ~ 0 ~ 0 ~ 0]^\top \f$, otherwise:
86 * \f[ \mathbf{q} = \left[ \begin{array}{c}
87 * \cos(\frac{\theta}{2}) \\
88 * v_x \frac{\sin(\frac{\theta}{2})}{\theta} \\
89 * v_y \frac{\sin(\frac{\theta}{2})}{\theta} \\
90 * v_z \frac{\sin(\frac{\theta}{2})}{\theta}
91 * \end{array} \right] \f]
92 * where \f$ \theta = |\mathbf{v}| = \sqrt{v_x^2+v_y^2+v_z^2} \f$.
93 * \sa "Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors (2006)", James Diebel.
94 */
95 template <class ARRAYLIKE3>
96 void fromRodriguesVector(const ARRAYLIKE3 &v)
97 {
98 if (v.size()!=3) THROW_EXCEPTION("Vector v must have a length=3");
99
100 const T x = v[0];
101 const T y = v[1];
102 const T z = v[2];
103 const T angle = std::sqrt(x*x+y*y+z*z);
104 if (angle<1e-7)
105 {
106 (*this)[0] = 1;
107 (*this)[1] = static_cast<T>(0.5)*x;
108 (*this)[2] = static_cast<T>(0.5)*y;
109 (*this)[3] = static_cast<T>(0.5)*z;
110 }
111 else
112 {
113 const T s = (::sin(angle/2))/angle;
114 const T c = ::cos(angle/2);
115 (*this)[0] = c;
116 (*this)[1] = x * s;
117 (*this)[2] = y * s;
118 (*this)[3] = z * s;
119 }
120 }
121
122
123 /** @name Lie Algebra methods
124 @{ */
125
126
127 /** Logarithm of the 3x3 matrix defined by this pose, generating the corresponding vector in the SO(3) Lie Algebra,
128 * which coincides with the so-called "rotation vector" (I don't have space here for the proof ;-).
129 * \param[out] out_ln The target vector, which can be: std::vector<>, or mrpt::math::CVectorDouble or any row or column Eigen::Matrix<>.
130 * \sa exp, mrpt::poses::SE_traits */
131 template <class ARRAYLIKE3>
132 inline void ln(ARRAYLIKE3 &out_ln) const
133 {
134 if (out_ln.size()!=3) out_ln.resize(3);
135 this->ln_noresize(out_ln);
136 }
137 /** \overload that returns by value */
138 template <class ARRAYLIKE3>
139 inline ARRAYLIKE3 ln() const
140 {
141 ARRAYLIKE3 out_ln;
142 this->ln(out_ln);
143 return out_ln;
144 }
145 /** Like ln() but does not try to resize the output vector. */
146 template <class ARRAYLIKE3>
147 void ln_noresize(ARRAYLIKE3 &out_ln) const
148 {
150 const T xyz_norm = std::sqrt(square(x())+square(y())+square(z()));
151 const T K = (xyz_norm<1e-7) ? 2 : 2*::acos(r())/xyz_norm;
152 out_ln[0] = K*x();
153 out_ln[1] = K*y();
154 out_ln[2] = K*z();
155 }
156
157 /** Exponential map from the SO(3) Lie Algebra to unit quaternions.
158 * \sa ln, mrpt::poses::SE_traits */
159 template <class ARRAYLIKE3>
160 inline static CQuaternion<T> exp(const ARRAYLIKE3 & v)
161 {
164 return q;
165 }
166 /** \overload */
167 template <class ARRAYLIKE3>
168 inline static void exp(const ARRAYLIKE3 & v, CQuaternion<T> & out_quat)
169 {
170 out_quat.fromRodriguesVector(v);
171 }
172
173 /** @} */ // end of Lie algebra
174
175
176 /** Calculate the "cross" product (or "composed rotation") of two quaternion: this = q1 x q2
177 * After the operation, "this" will represent the composed rotations of q1 and q2 (q2 applied "after" q1).
178 */
179 inline void crossProduct(const CQuaternion &q1, const CQuaternion &q2)
180 {
181 // First: compute result, then save in this object. In this way we avoid problems when q1 or q2 == *this !!
182 const T new_r = q1.r()*q2.r() - q1.x()*q2.x() - q1.y()*q2.y() - q1.z()*q2.z();
183 const T new_x = q1.r()*q2.x() + q2.r()*q1.x() + q1.y()*q2.z() - q2.y()*q1.z();
184 const T new_y = q1.r()*q2.y() + q2.r()*q1.y() + q1.z()*q2.x() - q2.z()*q1.x();
185 const T new_z = q1.r()*q2.z() + q2.r()*q1.z() + q1.x()*q2.y() - q2.x()*q1.y();
186 this->r(new_r); this->x(new_x); this->y(new_y); this->z(new_z);
187 this->normalize();
188 }
189
190 /** Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by this quaternion
191 */
192 void rotatePoint(const double lx,const double ly,const double lz, double &gx,double &gy,double &gz ) const
193 {
194 const double t2 = r()*x(); const double t3 = r()*y(); const double t4 = r()*z(); const double t5 =-x()*x(); const double t6 = x()*y();
195 const double t7 = x()*z(); const double t8 =-y()*y(); const double t9 = y()*z(); const double t10=-z()*z();
196 gx = 2*((t8+ t10)*lx+(t6 - t4)*ly+(t3+t7)*lz)+lx;
197 gy = 2*((t4+ t6)*lx+(t5 +t10)*ly+(t9-t2)*lz)+ly;
198 gz = 2*((t7- t3)*lx+(t2 + t9)*ly+(t5+t8)*lz)+lz;
199 }
200
201 /** Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by the inverse (conjugate) of this quaternion
202 */
203 void inverseRotatePoint(const double lx,const double ly,const double lz, double &gx,double &gy,double &gz ) const
204 {
205 const double t2 =-r()*x(); const double t3 =-r()*y(); const double t4 =-r()*z(); const double t5 =-x()*x(); const double t6 = x()*y();
206 const double t7 = x()*z(); const double t8 =-y()*y(); const double t9 = y()*z(); const double t10=-z()*z();
207 gx = 2*((t8+ t10)*lx+(t6 - t4)*ly+(t3+t7)*lz)+lx;
208 gy = 2*((t4+ t6)*lx+(t5 +t10)*ly+(t9-t2)*lz)+ly;
209 gz = 2*((t7- t3)*lx+(t2 + t9)*ly+(t5+t8)*lz)+lz;
210 }
211
212 /** Return the squared norm of the quaternion */
213 inline double normSqr() const {
215 return square(r()) + square(x()) + square(y()) + square(z());
216 }
217
218 /** Normalize this quaternion, so its norm becomes the unitity.
219 */
220 inline void normalize()
221 {
222 const T qq = 1.0/std::sqrt( normSqr() );
223 for (unsigned int i=0;i<4;i++)
224 (*this)[i] *= qq;
225 }
226
227 /** Calculate the 4x4 Jacobian of the normalization operation of this quaternion.
228 * The output matrix can be a dynamic or fixed size (4x4) matrix.
229 */
230 template <class MATRIXLIKE>
231 void normalizationJacobian(MATRIXLIKE &J) const
232 {
233 const T n = 1.0/std::pow(normSqr(),T(1.5));
234 J.setSize(4,4);
235 J.get_unsafe(0,0)=x()*x()+y()*y()+z()*z();
236 J.get_unsafe(0,1)=-r()*x();
237 J.get_unsafe(0,2)=-r()*y();
238 J.get_unsafe(0,3)=-r()*z();
239
240 J.get_unsafe(1,0)=-x()*r();
241 J.get_unsafe(1,1)=r()*r()+y()*y()+z()*z();
242 J.get_unsafe(1,2)=-x()*y();
243 J.get_unsafe(1,3)=-x()*z();
244
245 J.get_unsafe(2,0)=-y()*r();
246 J.get_unsafe(2,1)=-y()*x();
247 J.get_unsafe(2,2)=r()*r()+x()*x()+z()*z();
248 J.get_unsafe(2,3)=-y()*z();
249
250 J.get_unsafe(3,0)=-z()*r();
251 J.get_unsafe(3,1)=-z()*x();
252 J.get_unsafe(3,2)=-z()*y();
253 J.get_unsafe(3,3)=r()*r()+x()*x()+y()*y();
254 J *=n;
255 }
256
257 /** Compute the Jacobian of the rotation composition operation \f$ p = f(\cdot) = q_{this} \times r \f$, that is the 4x4 matrix \f$ \frac{\partial f}{\partial q_{this} } \f$.
258 * The output matrix can be a dynamic or fixed size (4x4) matrix.
259 */
260 template <class MATRIXLIKE>
261 inline void rotationJacobian(MATRIXLIKE &J) const
262 {
263 J.setSize(4,4);
264 J.get_unsafe(0,0)=r(); J.get_unsafe(0,1)=-x(); J.get_unsafe(0,2)=-y(); J.get_unsafe(0,3)=-z();
265 J.get_unsafe(1,0)=x(); J.get_unsafe(1,1)= r(); J.get_unsafe(1,2)=-z(); J.get_unsafe(1,3)= y();
266 J.get_unsafe(2,0)=y(); J.get_unsafe(2,1)= z(); J.get_unsafe(2,2)= r(); J.get_unsafe(2,3)=-x();
267 J.get_unsafe(3,0)=z(); J.get_unsafe(3,1)=-y(); J.get_unsafe(3,2)= x(); J.get_unsafe(3,3)= r();
268 }
269
270 /** Calculate the 3x3 rotation matrix associated to this quaternion: \f[ \mathbf{R} = \left(
271 * \begin{array}{ccc}
272 * q_r^2+q_x^2-q_y^2-q_z^2 & 2(q_x q_y - q_r q_z) & 2(q_z q_x+q_r q_y) \\
273 * 2(q_x q_y+q_r q_z) & q_r^2-q_x^2+q_y^2-q_z^2 & 2(q_y q_z-q_r q_x) \\
274 * 2(q_z q_x-q_r q_y) & 2(q_y q_z+q_r q_x) & q_r^2- q_x^2 - q_y^2 + q_z^2
275 * \end{array}
276 * \right)\f]
277 *
278 */
279 template <class MATRIXLIKE>
280 inline void rotationMatrix(MATRIXLIKE &M) const
281 {
282 M.setSize(3,3);
284 }
285
286 /** Fill out the top-left 3x3 block of the given matrix with the rotation matrix associated to this quaternion (does not resize the matrix, for that, see rotationMatrix). */
287 template <class MATRIXLIKE>
288 inline void rotationMatrixNoResize(MATRIXLIKE &M) const
289 {
290 M.get_unsafe(0,0)=r()*r()+x()*x()-y()*y()-z()*z(); M.get_unsafe(0,1)=2*(x()*y() -r()*z()); M.get_unsafe(0,2)=2*(z()*x()+r()*y());
291 M.get_unsafe(1,0)=2*(x()*y()+r()*z()); M.get_unsafe(1,1)=r()*r()-x()*x()+y()*y()-z()*z(); M.get_unsafe(1,2)=2*(y()*z()-r()*x());
292 M.get_unsafe(2,0)=2*(z()*x()-r()*y()); M.get_unsafe(2,1)=2*(y()*z()+r()*x()); M.get_unsafe(2,2)=r()*r()-x()*x()-y()*y()+z()*z();
293 }
294
295
296 /** Return the conjugate quaternion */
297 inline void conj(CQuaternion &q_out) const
298 {
299 q_out.r( r() );
300 q_out.x(-x() );
301 q_out.y(-y() );
302 q_out.z(-z() );
303 }
304
305 /** Return the conjugate quaternion */
306 inline CQuaternion conj() const
307 {
308 CQuaternion q_aux;
309 conj(q_aux);
310 return q_aux;
311 }
312
313 /** Return the yaw, pitch & roll angles associated to quaternion
314 * \sa For the equations, see The MRPT Book, or see http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/Quaternions.pdf
315 * \sa rpy_and_jacobian
316 */
317 inline void rpy(T &roll, T &pitch, T &yaw) const
318 {
319 rpy_and_jacobian(roll,pitch,yaw,static_cast<mrpt::math::CMatrixDouble*>(NULL));
320 }
321
322 /** Return the yaw, pitch & roll angles associated to quaternion, and (optionally) the 3x4 Jacobian of the transformation.
323 * Note that both the angles and the Jacobian have one set of normal equations, plus other special formulas for the degenerated cases of |pitch|=90 degrees.
324 * \sa For the equations, see The MRPT Book, or http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/Quaternions.pdf
325 * \sa rpy
326 */
327 template <class MATRIXLIKE>
328 void rpy_and_jacobian(T &roll, T &pitch, T &yaw, MATRIXLIKE *out_dr_dq = NULL, bool resize_out_dr_dq_to3x4 = true ) const
329 {
331 using std::sqrt;
332
333 if (out_dr_dq && resize_out_dr_dq_to3x4)
334 out_dr_dq->setSize(3,4);
335 const T discr = r()*y()-x()*z();
336 if (fabs(discr)>0.49999)
337 { // pitch = 90 deg
338 pitch = 0.5*M_PI;
339 yaw =-2*atan2(x(),r());
340 roll = 0;
341 if (out_dr_dq) {
342 out_dr_dq->zeros();
343 out_dr_dq->get_unsafe(0,0) = +2/x();
344 out_dr_dq->get_unsafe(0,2) = -2*r()/(x()*x());
345 }
346 }
347 else if (discr<-0.49999)
348 { // pitch =-90 deg
349 pitch = -0.5*M_PI;
350 yaw = 2*atan2(x(),r());
351 roll = 0;
352 if (out_dr_dq) {
353 out_dr_dq->zeros();
354 out_dr_dq->get_unsafe(0,0) = -2/x();
355 out_dr_dq->get_unsafe(0,2) = +2*r()/(x()*x());
356 }
357 }
358 else
359 { // Non-degenerate case:
360 yaw = ::atan2( 2*(r()*z()+x()*y()), 1-2*(y()*y()+z()*z()) );
361 pitch = ::asin ( 2*discr );
362 roll = ::atan2( 2*(r()*x()+y()*z()), 1-2*(x()*x()+y()*y()) );
363 if (out_dr_dq) {
364 // Auxiliary terms:
365 const double val1=(2*x()*x() + 2*y()*y() - 1);
366 const double val12=square(val1);
367 const double val2=(2*r()*x() + 2*y()*z());
368 const double val22=square(val2);
369 const double xy2 = 2*x()*y();
370 const double rz2 = 2*r()*z();
371 const double ry2 = 2*r()*y();
372 const double val3 = (2*y()*y() + 2*z()*z() - 1);
373 const double val4 = ((square(rz2 + xy2)/square(val3) + 1)*val3);
374 const double val5 = (4*(rz2 + xy2))/square(val3);
375 const double val6 = 1.0/(square(rz2 + xy2)/square(val3) + 1);
376 const double val7 = 2.0/ sqrt(1 - square(ry2 - 2*x()*z()));
377 const double val8 = (val22/val12 + 1);
378 const double val9 = -2.0/val8;
379 // row 1:
380 out_dr_dq->get_unsafe(0,0) = -2*z()/val4;
381 out_dr_dq->get_unsafe(0,1) = -2*y()/val4;
382 out_dr_dq->get_unsafe(0,2) = -(2*x()/val3 - y()*val5)*val6 ;
383 out_dr_dq->get_unsafe(0,3) = -(2*r()/val3 - z()*val5)*val6;
384 // row 2:
385 out_dr_dq->get_unsafe(1,0) = y()*val7 ;
386 out_dr_dq->get_unsafe(1,1) = -z()*val7 ;
387 out_dr_dq->get_unsafe(1,2) = r()*val7 ;
388 out_dr_dq->get_unsafe(1,3) = -x()*val7 ;
389 // row 3:
390 out_dr_dq->get_unsafe(2,0) = val9*x()/val1 ;
391 out_dr_dq->get_unsafe(2,1) = val9*(r()/val1 - (2*x()*val2)/val12) ;
392 out_dr_dq->get_unsafe(2,2) = val9*(z()/val1 - (2*y()*val2)/val12) ;
393 out_dr_dq->get_unsafe(2,3) = val9*y()/val1 ;
394 }
395 }
396 }
397
398 inline CQuaternion operator * (const T &factor)
399 {
400 CQuaternion q = *this;
401 q*=factor;
402 return q;
403 }
404
405 }; // end class
406
407 typedef CQuaternion<double> CQuaternionDouble; //!< A quaternion of data type "double"
408 typedef CQuaternion<float> CQuaternionFloat; //!< A quaternion of data type "float"
409
410 } // end namespace
411
412} // end namespace mrpt
413
414#endif
#define M_PI
Definition: bits.h:65
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually,...
Definition: CArrayNumeric.h:26
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ,...
Definition: CQuaternion.h:43
void fromRodriguesVector(const ARRAYLIKE3 &v)
Set this quaternion to the rotation described by a 3D (Rodrigues) rotation vector : If ,...
Definition: CQuaternion.h:96
CQuaternion()
Default constructor: construct a (1, (0,0,0) ) quaternion representing no rotation.
Definition: CQuaternion.h:53
T z() const
Return z coordinate of the quaternion.
Definition: CQuaternion.h:78
CQuaternion(const T r, const T x, const T y, const T z)
Construct a quaternion from its parameters 'r', 'x', 'y', 'z', with q = r + ix + jy + kz.
Definition: CQuaternion.h:62
ARRAYLIKE3 ln() const
Definition: CQuaternion.h:139
T x() const
Return x coordinate of the quaternion.
Definition: CQuaternion.h:76
void z(const T z)
Set z coordinate of the quaternion.
Definition: CQuaternion.h:82
void rpy(T &roll, T &pitch, T &yaw) const
Return the yaw, pitch & roll angles associated to quaternion.
Definition: CQuaternion.h:317
void rotationJacobian(MATRIXLIKE &J) const
Compute the Jacobian of the rotation composition operation , that is the 4x4 matrix .
Definition: CQuaternion.h:261
CQuaternion operator*(const T &factor)
Definition: CQuaternion.h:398
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...
Definition: CQuaternion.h:179
static void exp(const ARRAYLIKE3 &v, CQuaternion< T > &out_quat)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CQuaternion.h:168
static CQuaternion< T > exp(const ARRAYLIKE3 &v)
Exponential map from the SO(3) Lie Algebra to unit quaternions.
Definition: CQuaternion.h:160
void rotatePoint(const double lx, const double ly, const double lz, double &gx, double &gy, double &gz) const
Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by this quaternion.
Definition: CQuaternion.h:192
T r() const
Return r coordinate of the quaternion.
Definition: CQuaternion.h:75
double normSqr() const
Return the squared norm of the quaternion.
Definition: CQuaternion.h:213
T y() const
Return y coordinate of the quaternion.
Definition: CQuaternion.h:77
void conj(CQuaternion &q_out) const
Return the conjugate quaternion
Definition: CQuaternion.h:297
void rotationMatrix(MATRIXLIKE &M) const
Calculate the 3x3 rotation matrix associated to this quaternion:
Definition: CQuaternion.h:280
void rotationMatrixNoResize(MATRIXLIKE &M) const
Fill out the top-left 3x3 block of the given matrix with the rotation matrix associated to this quate...
Definition: CQuaternion.h:288
void ln_noresize(ARRAYLIKE3 &out_ln) const
Like ln() but does not try to resize the output vector.
Definition: CQuaternion.h:147
void r(const T r)
Set r coordinate of the quaternion.
Definition: CQuaternion.h:79
void rpy_and_jacobian(T &roll, T &pitch, T &yaw, MATRIXLIKE *out_dr_dq=NULL, bool resize_out_dr_dq_to3x4=true) const
Return the yaw, pitch & roll angles associated to quaternion, and (optionally) the 3x4 Jacobian of th...
Definition: CQuaternion.h:328
void y(const T y)
Set y coordinate of the quaternion.
Definition: CQuaternion.h:81
void inverseRotatePoint(const double lx, const double ly, const double lz, double &gx, double &gy, double &gz) const
Rotate a 3D point (lx,ly,lz) -> (gx,gy,gz) as described by the inverse (conjugate) of this quaternion...
Definition: CQuaternion.h:203
CQuaternion(TConstructorFlags_Quaternions)
Can be used with UNINITIALIZED_QUATERNION as argument, does not initialize the 4 elements of the quat...
Definition: CQuaternion.h:50
CQuaternion conj() const
Return the conjugate quaternion
Definition: CQuaternion.h:306
void ln(ARRAYLIKE3 &out_ln) const
Logarithm of the 3x3 matrix defined by this pose, generating the corresponding vector in the SO(3) Li...
Definition: CQuaternion.h:132
void normalizationJacobian(MATRIXLIKE &J) const
Calculate the 4x4 Jacobian of the normalization operation of this quaternion.
Definition: CQuaternion.h:231
CArrayNumeric< T, 4 > Base
Definition: CQuaternion.h:44
void x(const T x)
Set x coordinate of the quaternion.
Definition: CQuaternion.h:80
void normalize()
Normalize this quaternion, so its norm becomes the unitity.
Definition: CQuaternion.h:220
#define THROW_EXCEPTION(msg)
Definition: mrpt_macros.h:110
#define ASSERTMSG_(f, __ERROR_MSG)
Definition: mrpt_macros.h:260
CQuaternion< float > CQuaternionFloat
A quaternion of data type "float".
Definition: CQuaternion.h:408
TConstructorFlags_Quaternions
Definition: CQuaternion.h:22
@ UNINITIALIZED_QUATERNION
Definition: CQuaternion.h:23
CQuaternion< double > CQuaternionDouble
A quaternion of data type "double".
Definition: CQuaternion.h:407
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:113
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.



Page generated by Doxygen 1.9.5 for MRPT 1.4.0 SVN: at Sun Nov 27 02:56:26 UTC 2022