Main MRPT website > C++ reference for MRPT 1.9.9
CPose3DQuat.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, 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 #include "base-precomp.h" // Precompiled headers
11 #include <mrpt/poses/CPose3D.h>
12 #include <mrpt/poses/CPose3DQuat.h>
13 #include <mrpt/utils/CStream.h>
14 #include <iomanip>
15 #include <limits>
16 
17 using namespace std;
18 using namespace mrpt;
19 using namespace mrpt::math;
20 using namespace mrpt::utils;
21 using namespace mrpt::poses;
22 
24 
25 /** Constructor from a CPose3D */
27 {
28  x() = p.x();
29  y() = p.y();
30  z() = p.z();
31  p.getAsQuaternion(m_quat);
32 }
33 
34 /** Constructor from a 4x4 homogeneous transformation matrix.
35  */
36 CPose3DQuat::CPose3DQuat(const CMatrixDouble44& M)
37  : m_quat(UNINITIALIZED_QUATERNION)
38 {
39  m_coords[0] = M.get_unsafe(0, 3);
40  m_coords[1] = M.get_unsafe(1, 3);
41  m_coords[2] = M.get_unsafe(2, 3);
42  CPose3D p(M);
43  p.getAsQuaternion(m_quat);
44 }
45 
46 /** Returns the corresponding 4x4 homogeneous transformation matrix for the
47  * point(translation) or pose (translation+orientation).
48  * \sa getInverseHomogeneousMatrix
49  */
51 {
53  out_HM.get_unsafe(0, 3) = m_coords[0];
54  out_HM.get_unsafe(1, 3) = m_coords[1];
55  out_HM.get_unsafe(2, 3) = m_coords[2];
56  out_HM.get_unsafe(3, 0) = out_HM.get_unsafe(3, 1) =
57  out_HM.get_unsafe(3, 2) = 0;
58  out_HM.get_unsafe(3, 3) = 1;
59 }
60 
61 /** Returns a 1x7 vector with [x y z qr qx qy qz] */
63 {
64  v.resize(7);
65  v[0] = m_coords[0];
66  v[1] = m_coords[1];
67  v[2] = m_coords[2];
68  v[3] = m_quat[0];
69  v[4] = m_quat[1];
70  v[5] = m_quat[2];
71  v[6] = m_quat[3];
72 }
73 
74 /** Makes "this = A (+) B"; this method is slightly more efficient than "this=
75  * A + B;" since it avoids the temporary object.
76  * \note A or B can be "this" without problems.
77  */
79 {
80  // The 3D point:
81  double gx, gy, gz;
83  B.m_coords[0], B.m_coords[1], B.m_coords[2], gx, gy, gz);
84  this->m_coords[0] = A.m_coords[0] + gx;
85  this->m_coords[1] = A.m_coords[1] + gy;
86  this->m_coords[2] = A.m_coords[2] + gz;
87 
88  // The 3D rotation:
89  this->m_quat.crossProduct(A.m_quat, B.m_quat);
90 }
91 
92 /** Makes \f$ this = A \ominus B \f$ this method is slightly more efficient
93  * than "this= A - B;" since it avoids the temporary object.
94  * \note A or B can be "this" without problems.
95  * \sa composeFrom
96  */
98 {
99  // The 3D point:
100  const CQuaternionDouble B_conj(
101  B.m_quat.r(), -B.m_quat.x(), -B.m_quat.y(), -B.m_quat.z());
102  B_conj.rotatePoint(
103  A.m_coords[0] - B.m_coords[0], A.m_coords[1] - B.m_coords[1],
104  A.m_coords[2] - B.m_coords[2], this->m_coords[0], this->m_coords[1],
105  this->m_coords[2]);
106  // The 3D rotation:
107  this->m_quat.crossProduct(B_conj, A.m_quat);
108 }
109 
110 /** Computes the 3D point G such as \f$ G = this \oplus L \f$.
111  * \sa inverseComposeFrom
112  */
114  const double lx, const double ly, const double lz, double& gx, double& gy,
115  double& gz,
116  mrpt::math::CMatrixFixedNumeric<double, 3, 3>* out_jacobian_df_dpoint,
117  mrpt::math::CMatrixFixedNumeric<double, 3, 7>* out_jacobian_df_dpose) const
118 {
119  if (out_jacobian_df_dpoint || out_jacobian_df_dpose)
120  {
121  const double qx2 = square(m_quat.x());
122  const double qy2 = square(m_quat.y());
123  const double qz2 = square(m_quat.z());
124 
125  // Jacob: df/dpoint
126  if (out_jacobian_df_dpoint)
127  {
128  // 3x3: df_{qr} / da
129 
130  alignas(16) const double vals[3 * 3] = {
131  1 - 2 * (qy2 + qz2),
132  2 * (m_quat.x() * m_quat.y() - m_quat.r() * m_quat.z()),
133  2 * (m_quat.r() * m_quat.y() + m_quat.x() * m_quat.z()),
134 
135  2 * (m_quat.r() * m_quat.z() + m_quat.x() * m_quat.y()),
136  1 - 2 * (qx2 + qz2),
137  2 * (m_quat.y() * m_quat.z() - m_quat.r() * m_quat.x()),
138 
139  2 * (m_quat.x() * m_quat.z() - m_quat.r() * m_quat.y()),
140  2 * (m_quat.r() * m_quat.x() + m_quat.y() * m_quat.z()),
141  1 - 2 * (qx2 + qy2)};
142  out_jacobian_df_dpoint->loadFromArray(vals);
143  }
144 
145  // Jacob: df/dpose
146  if (out_jacobian_df_dpose)
147  {
148  // 3x7: df_{qr} / dp
149  alignas(16) const double vals1[3 * 7] = {
150  1, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0};
151  out_jacobian_df_dpose->loadFromArray(vals1);
152 
153  alignas(16) const double vals[3 * 4] = {
154  2 * (-m_quat.z() * ly + m_quat.y() * lz),
155  2 * (m_quat.y() * ly + m_quat.z() * lz),
156  2 * (-2 * m_quat.y() * lx + m_quat.x() * ly + m_quat.r() * lz),
157  2 * (-2 * m_quat.z() * lx - m_quat.r() * ly + m_quat.x() * lz),
158 
159  2 * (m_quat.z() * lx - m_quat.x() * lz),
160  2 * (m_quat.y() * lx - 2 * m_quat.x() * ly - m_quat.r() * lz),
161  2 * (m_quat.x() * lx + m_quat.z() * lz),
162  2 * (m_quat.r() * lx - 2 * m_quat.z() * ly + m_quat.y() * lz),
163 
164  2 * (-m_quat.y() * lx + m_quat.x() * ly),
165  2 * (m_quat.z() * lx + m_quat.r() * ly - 2 * m_quat.x() * lz),
166  2 * (-m_quat.r() * lx + m_quat.z() * ly - 2 * m_quat.y() * lz),
167  2 * (m_quat.x() * lx + m_quat.y() * ly)};
168 
170  this->quat().normalizationJacobian(norm_jacob);
171 
172  out_jacobian_df_dpose->insertMatrix(
173  0, 3,
174  (CMatrixFixedNumeric<double, 3, 4>(vals) * norm_jacob).eval());
175  }
176  }
177 
178  // function itself:
179  m_quat.rotatePoint(lx, ly, lz, gx, gy, gz);
180  gx += m_coords[0];
181  gy += m_coords[1];
182  gz += m_coords[2];
183 }
184 
185 /** Computes the 3D point G such as \f$ L = G \ominus this \f$.
186  * \sa composeFrom
187  */
189  const double gx, const double gy, const double gz, double& lx, double& ly,
190  double& lz,
191  mrpt::math::CMatrixFixedNumeric<double, 3, 3>* out_jacobian_df_dpoint,
192  mrpt::math::CMatrixFixedNumeric<double, 3, 7>* out_jacobian_df_dpose) const
193 {
194  if (out_jacobian_df_dpoint || out_jacobian_df_dpose)
195  {
196  const double qx2 = square(m_quat.x());
197  const double qy2 = square(m_quat.y());
198  const double qz2 = square(m_quat.z());
199 
200  // Jacob: df/dpoint
201  if (out_jacobian_df_dpoint)
202  {
203  // 3x3: df_{m_quat.r()} / da
204  // inv_df_da =
205  // [ - 2*qy^2 - 2*qz^2 + 1, 2*qx*qy - 2*qr*qz, 2*qr*qy
206  //+
207  // 2*qx*qz]
208  // [ 2*qr*qz + 2*qx*qy, - 2*qx^2 - 2*qz^2 + 1, 2*qy*qz
209  //-
210  // 2*qr*qx]
211  // [ 2*qx*qz - 2*qr*qy, 2*qr*qx + 2*qy*qz, - 2*qx^2 -
212  // 2*qy^2 + 1]
213  //
214 
215  alignas(16) const double vals[3 * 3] = {
216  1 - 2 * (qy2 + qz2),
217  2 * (m_quat.x() * m_quat.y() + m_quat.r() * m_quat.z()),
218  2 * (-m_quat.r() * m_quat.y() + m_quat.x() * m_quat.z()),
219 
220  2 * (-m_quat.r() * m_quat.z() + m_quat.x() * m_quat.y()),
221  1 - 2 * (qx2 + qz2),
222  2 * (m_quat.y() * m_quat.z() + m_quat.r() * m_quat.x()),
223 
224  2 * (m_quat.x() * m_quat.z() + m_quat.r() * m_quat.y()),
225  2 * (-m_quat.r() * m_quat.x() + m_quat.y() * m_quat.z()),
226  1 - 2 * (qx2 + qy2)};
227  out_jacobian_df_dpoint->loadFromArray(vals);
228  }
229 
230  // Jacob: df/dpose
231  if (out_jacobian_df_dpose)
232  {
233  // 3x7: df_{m_quat.r()} / dp
234  // inv_df_dp =
235  //[ 2*qy^2 + 2*qz^2 - 1, - 2*qr*qz - 2*qx*qy, 2*qr*qy - 2*qx*qz,
236  // 2*qz*(ay - y) - 2*qy*(az - z), 2*qy*(ay - y) +
237  // 2*qz*(az - z), 2*qx*(ay - y) - 4*qy*(ax - x) - 2*qr*(az - z),
238  // 2*qr*(ay - y) - 4*qz*(ax - x) + 2*qx*(az - z)]
239  //[ 2*qr*qz - 2*qx*qy, 2*qx^2 + 2*qz^2 - 1, - 2*qr*qx - 2*qy*qz,
240  // 2*qx*(az - z) - 2*qz*(ax - x), 2*qy*(ax - x) - 4*qx*(ay - y) +
241  // 2*qr*(az - z), 2*qx*(ax - x) + 2*qz*(az - z),
242  // 2*qy*(az - z) - 4*qz*(ay - y) - 2*qr*(ax - x)]
243  //[ - 2*qr*qy - 2*qx*qz, 2*qr*qx - 2*qy*qz, 2*qx^2 + 2*qy^2 - 1,
244  // 2*qy*(ax - x) - 2*qx*(ay - y), 2*qz*(ax - x) - 2*qr*(ay - y) -
245  // 4*qx*(az - z), 2*qr*(ax - x) + 2*qz*(ay - y) - 4*qy*(az - z),
246  // 2*qx*(ax - x) + 2*qy*(ay - y)]
247  //
248  const double qr = m_quat.r();
249  const double qx = m_quat.x();
250  const double qy = m_quat.y();
251  const double qz = m_quat.z();
252 
253  alignas(16) const double vals1[3 * 7] = {
254  2 * qy2 + 2 * qz2 - 1,
255  -2 * qr * qz - 2 * qx * qy,
256  2 * qr * qy - 2 * qx * qz,
257  0,
258  0,
259  0,
260  0,
261 
262  2 * qr * qz - 2 * qx * qy,
263  2 * qx2 + 2 * qz2 - 1,
264  -2 * qr * qx - 2 * qy * qz,
265  0,
266  0,
267  0,
268  0,
269 
270  -2 * qr * qy - 2 * qx * qz,
271  2 * qr * qx - 2 * qy * qz,
272  2 * qx2 + 2 * qy2 - 1,
273  0,
274  0,
275  0,
276  0,
277  };
278 
279  out_jacobian_df_dpose->loadFromArray(vals1);
280 
281  const double Ax = 2 * (gx - m_coords[0]);
282  const double Ay = 2 * (gy - m_coords[1]);
283  const double Az = 2 * (gz - m_coords[2]);
284 
285  alignas(16)
286  const double vals[3 * 4] = {-qy * Az + qz * Ay,
287  qy * Ay + qz * Az,
288  qx * Ay - 2 * qy * Ax - qr * Az,
289  qx * Az + qr * Ay - 2 * qz * Ax,
290 
291  qx * Az - qz * Ax,
292  qy * Ax - 2 * qx * Ay + qr * Az,
293  qx * Ax + qz * Az,
294  qy * Az - 2 * qz * Ay - qr * Ax,
295 
296  qy * Ax - qx * Ay,
297  qz * Ax - qr * Ay - 2 * qx * Az,
298  qr * Ax + qz * Ay - 2 * qy * Az,
299  qx * Ax + qy * Ay};
300 
302  this->quat().normalizationJacobian(norm_jacob);
303 
304  out_jacobian_df_dpose->insertMatrix(
305  0, 3,
306  (CMatrixFixedNumeric<double, 3, 4>(vals) * norm_jacob).eval());
307  }
308  }
309 
310  // function itself:
312  gx - m_coords[0], gy - m_coords[1], gz - m_coords[2], lx, ly, lz);
313 }
314 
315 /*---------------------------------------------------------------
316  *=
317  ---------------------------------------------------------------*/
318 void CPose3DQuat::operator*=(const double s)
319 {
320  m_coords[0] *= s;
321  m_coords[1] *= s;
322  m_coords[2] *= s;
323  m_quat[0] *= s;
324  m_quat[1] *= s;
325  m_quat[2] *= s;
326  m_quat[3] *= s;
327 }
328 
329 /*---------------------------------------------------------------
330  Implements the writing to a CStream capability of
331  CSerializable objects
332  ---------------------------------------------------------------*/
333 void CPose3DQuat::writeToStream(mrpt::utils::CStream& out, int* version) const
334 {
335  if (version)
336  *version = 0;
337  else
338  {
339  out << m_coords[0] << m_coords[1] << m_coords[2] << m_quat[0]
340  << m_quat[1] << m_quat[2] << m_quat[3];
341  }
342 }
343 
344 /*---------------------------------------------------------------
345  Implements the reading from a CStream capability of
346  CSerializable objects
347  ---------------------------------------------------------------*/
349 {
350  switch (version)
351  {
352  case 0:
353  {
354  in >> m_coords[0] >> m_coords[1] >> m_coords[2] >> m_quat[0] >>
355  m_quat[1] >> m_quat[2] >> m_quat[3];
356  }
357  break;
358  default:
360  };
361 }
362 
363 /*---------------------------------------------------------------
364  sphericalCoordinates
365 ---------------------------------------------------------------*/
367  const TPoint3D& point, double& out_range, double& out_yaw,
368  double& out_pitch,
369  mrpt::math::CMatrixFixedNumeric<double, 3, 3>* out_jacob_dryp_dpoint,
370  mrpt::math::CMatrixFixedNumeric<double, 3, 7>* out_jacob_dryp_dpose) const
371 {
372  const bool comp_jacobs =
373  out_jacob_dryp_dpoint != nullptr || out_jacob_dryp_dpose != nullptr;
374 
375  // Pass to coordinates as seen from this 6D pose:
376  CMatrixFixedNumeric<double, 3, 3> jacob_dinv_dpoint,
377  *ptr_ja1 = comp_jacobs ? &jacob_dinv_dpoint : nullptr;
378  CMatrixFixedNumeric<double, 3, 7> jacob_dinv_dpose,
379  *ptr_ja2 = comp_jacobs ? &jacob_dinv_dpose : nullptr;
380 
381  TPoint3D local;
382  this->inverseComposePoint(
383  point.x, point.y, point.z, local.x, local.y, local.z, ptr_ja1, ptr_ja2);
384 
385  // Range:
386  out_range = local.norm();
387 
388  // Yaw:
389  if (local.y != 0 || local.x != 0)
390  out_yaw = atan2(local.y, local.x);
391  else
392  out_yaw = 0;
393 
394  // Pitch:
395  if (out_range != 0)
396  out_pitch = -asin(local.z / out_range);
397  else
398  out_pitch = 0;
399 
400  // Jacobians are:
401  // dryp_dpoint = dryp_dlocalpoint * dinv_dpoint
402  // dryp_dpose = dryp_dlocalpoint * dinv_dpose
403  if (comp_jacobs)
404  {
405  if (out_range == 0)
406  THROW_EXCEPTION("Jacobians are undefined for range=0")
407 
408  /* MATLAB:
409  syms H h_range h_yaw h_pitch real;
410  syms xi_ yi_ zi_ real;
411  h_range = sqrt(xi_^2+yi_^2+zi_^2);
412  h_yaw = atan(yi_/xi_);
413  % h_pitch = -asin(zi_/ sqrt( xi_^2 + yi_^2 + zi_^2 ) );
414  h_pitch = -atan(zi_, sqrt( xi_^2 + yi_^2) );
415  H=[ h_range ; h_yaw ; h_pitch ];
416  jacob_fesf_xyz=jacobian(H,[xi_ yi_ zi_])
417  */
418  const double _r = 1.0 / out_range;
419  const double x2 = square(local.x);
420  const double y2 = square(local.y);
421 
422  const double t2 = std::sqrt(x2 + y2);
423  const double _K = 1.0 / (t2 * square(out_range));
424 
425  double vals[3 * 3] = {local.x * _r,
426  local.y * _r,
427  local.z * _r,
428  -local.y / (x2 * (y2 / x2 + 1)),
429  1.0 / (local.x * (y2 / x2 + 1)),
430  0,
431  (local.x * local.z) * _K,
432  (local.y * local.z) * _K,
433  -t2 / square(out_range)};
434 
435  const CMatrixDouble33 dryp_dlocalpoint(vals);
436  if (out_jacob_dryp_dpoint)
437  out_jacob_dryp_dpoint->multiply(
438  dryp_dlocalpoint, jacob_dinv_dpoint);
439  if (out_jacob_dryp_dpose)
440  out_jacob_dryp_dpose->multiply(dryp_dlocalpoint, jacob_dinv_dpose);
441  }
442 }
443 
444 /** Textual output stream function.
445  */
446 std::ostream& mrpt::poses::operator<<(std::ostream& o, const CPose3DQuat& p)
447 {
448  const std::streamsize old_pre = o.precision();
449  const ios_base::fmtflags old_flags = o.flags();
450  o << "(x,y,z,qr,qx,qy,qz)=(" << std::fixed << std::setprecision(4)
451  << p.m_coords[0] << "," << p.m_coords[1] << "," << p.m_coords[2] << ","
452  << p.quat()[0] << "," << p.quat()[1] << "," << p.quat()[2] << ","
453  << p.quat()[3] << ")";
454  o.flags(old_flags);
455  o.precision(old_pre);
456  return o;
457 }
458 
459 /** Unary - operator: return the inverse pose "-p" (Note that is NOT the same
460  * than a pose with all its arguments multiplied by "-1") */
462 {
463  CPose3DQuat ret = p;
464  ret.inverse();
465  return ret;
466 }
467 
468 /** Convert this pose into its inverse, saving the result in itself. \sa
469  * operator- */
471 {
472  // Invert translation:
473  this->inverseComposePoint(0, 0, 0, m_coords[0], m_coords[1], m_coords[2]);
474 
475  // Invert rotation: [qr qx qy qz] ==> [qr -qx -qy -qz]
476  m_quat[1] = -m_quat[1];
477  m_quat[2] = -m_quat[2];
478  m_quat[3] = -m_quat[3];
479 }
480 
482 {
483  for (int i = 0; i < 3; i++)
484  m_coords[i] = std::numeric_limits<double>::quiet_NaN();
485 
486  for (int i = 0; i < 4; i++)
487  quat()[i] = std::numeric_limits<double>::quiet_NaN();
488 }
489 
491 {
492  return p1.quat() == p2.quat() && p1.x() == p2.x() && p1.y() == p2.y() &&
493  p1.z() == p2.z();
494 }
495 
497 {
498  return !(p1 == p2);
499 }
500 
502 {
503  CPoint3D L;
504  p.inverseComposePoint(G[0], G[1], G[2], L[0], L[1], L[2]);
505  return L;
506 }
507 
509  const mrpt::math::TPoint3D& G, const CPose3DQuat& p)
510 {
512  p.inverseComposePoint(G[0], G[1], G[2], L[0], L[1], L[2]);
513  return L;
514 }
#define local
Definition: zutil.h:47
void getAsVector(mrpt::math::CVectorDouble &v) const
Returns a 1x7 vector with [x y z qr qx qy qz].
Definition: CPose3DQuat.cpp:62
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:245
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
Definition: CPose3DQuat.h:60
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:135
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacobian_df_dpose=nullptr) const
Computes the 3D point L such as .
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
GLdouble GLdouble z
Definition: glext.h:3872
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:44
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
T y() const
Return y coordinate of the quaternion.
Definition: CQuaternion.h:91
#define THROW_EXCEPTION(msg)
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:360
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:42
void sphericalCoordinates(const mrpt::math::TPoint3D &point, double &out_range, double &out_yaw, double &out_pitch, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacob_dryp_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacob_dryp_dpose=nullptr) const
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object...
STL namespace.
void setToNaN() override
Set all data fields to quiet NaN.
GLdouble s
Definition: glext.h:3676
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:55
void composePoint(const double lx, const double ly, const double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacobian_df_dpose=nullptr) const
Computes the 3D point G such as .
void readFromStream(mrpt::utils::CStream &in, int version) override
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
T r() const
Return r coordinate of the quaternion.
Definition: CQuaternion.h:87
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:202
void composeFrom(const CPose3DQuat &A, const CPose3DQuat &B)
Makes this method is slightly more efficient than "this= A + B;" since it avoids the temporary objec...
Definition: CPose3DQuat.cpp:78
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
bool operator!=(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Definition: CPoint.h:171
CPose2D operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
Definition: CPose2D.cpp:328
void inverse()
Convert this pose into its inverse, saving the result in itself.
double x
X,Y,Z coordinates.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Definition: CPose3DQuat.h:48
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:224
void writeToStream(mrpt::utils::CStream &out, int *getVersion) const override
Introduces a pure virtual method responsible for writing to a CStream.
virtual void operator*=(const double s)
Scalar multiplication (all x y z qr qx qy qz elements are multiplied by the scalar).
A class used to store a 3D point.
Definition: CPoint3D.h:32
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z].
Definition: CPose3DQuat.h:54
const GLdouble * v
Definition: glext.h:3678
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
T x() const
Return x coordinate of the quaternion.
Definition: CQuaternion.h:89
void normalizationJacobian(MATRIXLIKE &J) const
Calculate the 4x4 Jacobian of the normalization operation of this quaternion.
Definition: CQuaternion.h:283
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Definition: CPoint.h:163
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
Definition: CPose3DQuat.cpp:50
GLuint in
Definition: glext.h:7274
void inverseComposeFrom(const CPose3DQuat &A, const CPose3DQuat &B)
Makes this method is slightly more efficient than "this= A - B;" since it avoids the temporary objec...
Definition: CPose3DQuat.cpp:97
GLenum GLint GLint y
Definition: glext.h:3538
mrpt::math::CQuaternionDouble m_quat
The quaternion.
Definition: CPose3DQuat.h:56
GLenum GLint x
Definition: glext.h:3538
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
Definition: CQuaternion.h:46
Lightweight 3D point.
T z() const
Return z coordinate of the quaternion.
Definition: CQuaternion.h:93
GLfloat GLfloat p
Definition: glext.h:6305
std::ostream & operator<<(std::ostream &o, const CPoint< DERIVEDCLASS > &p)
Dumps a point as a string [x,y] or [x,y,z].
Definition: CPoint.h:137



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019