32 p.getAsQuaternion(m_quat);
52 out_HM.get_unsafe(0,3) =
m_coords[0];
53 out_HM.get_unsafe(1,3) =
m_coords[1];
54 out_HM.get_unsafe(2,3) =
m_coords[2];
55 out_HM.get_unsafe(3,0) = out_HM.get_unsafe(3,1) = out_HM.get_unsafe(3,2) = 0;
56 out_HM.get_unsafe(3,3) = 1;
109 if (out_jacobian_df_dpoint || out_jacobian_df_dpose)
116 if (out_jacobian_df_dpoint)
137 if (out_jacobian_df_dpose)
185 if (out_jacobian_df_dpoint || out_jacobian_df_dpose)
192 if (out_jacobian_df_dpoint)
218 if (out_jacobian_df_dpose)
251 const double Ax = 2*(gx -
m_coords[0]);
252 const double Ay = 2*(gy -
m_coords[1]);
253 const double Az = 2*(gz -
m_coords[2]);
258 qx*Ay - 2*qy*Ax - qr*Az ,
259 qx*Az + qr*Ay - 2*qz*Ax ,
262 qy*Ax - 2*qx*Ay + qr*Az,
264 qy*Az - 2*qz*Ay - qr*Ax,
267 qz*Ax - qr*Ay - 2*qx*Az,
268 qr*Ax + qz*Ay - 2*qy*Az,
341 const bool comp_jacobs = out_jacob_dryp_dpoint!=NULL || out_jacob_dryp_dpose!=NULL;
351 out_range =
local.norm();
360 out_pitch = -asin(
local.z / out_range );
381 const double _r = 1.0/out_range;
385 const double t2 = std::sqrt(x2 + y2);
386 const double _K = 1.0/(t2*
square(out_range));
390 -
local.y/(x2*(y2/x2 + 1)), 1.0/(
local.x*(y2/x2 + 1)), 0,
395 if (out_jacob_dryp_dpoint)
396 out_jacob_dryp_dpoint->multiply(dryp_dlocalpoint,jacob_dinv_dpoint);
397 if (out_jacob_dryp_dpose)
398 out_jacob_dryp_dpose->multiply(dryp_dlocalpoint,jacob_dinv_dpose);
407 const std::streamsize old_pre = o.precision();
408 const ios_base::fmtflags old_flags = o.flags();
409 o <<
"(x,y,z,qr,qx,qy,qz)=(" << std::fixed << std::setprecision(4)
410 <<
p.m_coords[0] <<
"," 411 <<
p.m_coords[1] <<
"," 412 <<
p.m_coords[2] <<
"," 413 <<
p.quat()[0] <<
"," 414 <<
p.quat()[1] <<
"," 415 <<
p.quat()[2] <<
"," 416 <<
p.quat()[3] <<
")";
418 o.precision(old_pre);
447 for (
int i=0;i<3;i++)
448 m_coords[i] = std::numeric_limits<double>::quiet_NaN();
450 for (
int i=0;i<4;i++)
451 quat()[i] = std::numeric_limits<double>::quiet_NaN();
456 return p1.
quat()==p2.
quat() && p1.
x()==p2.
x() && p1.
y()==p2.
y() && p1.z()==p2.z();
467 p.inverseComposePoint(G[0], G[1], G[2], L[0], L[1], L[2]);
474 p.inverseComposePoint(G[0], G[1], G[2], L[0], L[1], L[2]);
void readFromStream(mrpt::utils::CStream &in, int version)
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
void getAsVector(mrpt::math::CVectorDouble &v) const
Returns a 1x7 vector with [x y z qr qx qy qz].
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...
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
double x() const
Common members of all points & poses classes.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
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=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacob_dryp_dpose=NULL) const
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object...
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=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacobian_df_dpose=NULL) const
Computes the 3D point G such as .
The virtual base class which provides a unified interface for all persistent objects in MRPT...
T y() const
Return y coordinate of the quaternion.
#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...
void setToNaN() MRPT_OVERRIDE
Set all data fields to quiet NaN.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
double z
X,Y,Z coordinates.
IMPLEMENTS_SERIALIZABLE(CLogFileRecord_FullEval, CHolonomicLogFileRecord, mrpt::nav) IMPLEMENTS_SERIALIZABLE(CHolonomicFullEval
void writeToStream(mrpt::utils::CStream &out, int *getVersion) const
Introduces a pure virtual method responsible for writing to a CStream.
T square(const T x)
Inline function for the square of a number.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
T r() const
Return r coordinate of the quaternion.
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...
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...
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
bool operator!=(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
CPose2D BASE_IMPEXP operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
void inverse()
Convert this pose into its inverse, saving the result in itself.
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=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 7 > *out_jacobian_df_dpose=NULL) const
Computes the 3D point L such as .
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
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.
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.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void loadFromArray(const T *vals)
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z].
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
T x() const
Return x coordinate of the quaternion.
void normalizationJacobian(MATRIXLIKE &J) const
Calculate the 4x4 Jacobian of the normalization operation of this quaternion.
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
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...
mrpt::math::CQuaternionDouble m_quat
The quaternion.
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
T z() const
Return z coordinate of the quaternion.
std::ostream & operator<<(std::ostream &o, const CPoint< DERIVEDCLASS > &p)
Dumps a point as a string [x,y] or [x,y,z].