Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes
mrpt::poses::CPose3DQuat Class Reference

Detailed Description

A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).

For a complete description of Points/Poses, see mrpt::poses::CPoseOrPoint, or refer to the 2D/3D Geometry tutorial in the wiki.

To access the translation use x(), y() and z(). To access the rotation, use CPose3DQuat::quat().

This class also behaves like a STL container, since it has begin(), end(), iterators, and can be accessed with the [] operator with indices running from 0 to 6 to access the [x y z qr qx qy qz] as if they were a vector. Thus, a CPose3DQuat can be used as a 7-vector anywhere the MRPT math functions expect any kind of vector.

This class and CPose3D are very similar, and they can be converted to the each other automatically via transformation constructors.

See also
CPose3D (for a class based on a 4x4 matrix instead of a quaternion), mrpt::math::TPose3DQuat, mrpt::poses::CPose3DQuatPDF for a probabilistic version of this class, mrpt::math::CQuaternion, CPoseOrPoint

Definition at line 41 of file CPose3DQuat.h.

#include <mrpt/poses/CPose3DQuat.h>

Inheritance diagram for mrpt::poses::CPose3DQuat:
Inheritance graph

Classes

struct  const_iterator
 
struct  iterator
 

Public Types

enum  { is_3D_val = 1 }
 
enum  { rotation_dimensions = 3 }
 
enum  { is_PDF_val = 1 }
 
typedef CPose3DQuat type_value
 Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses.
 
typedef CPose3DQuat mrpt_autotype
 See ops_containers.h.
 

Public Member Functions

mrpt::math::CQuaternionDoublequat ()
 Read/Write access to the quaternion representing the 3D rotation.
 
const mrpt::math::CQuaternionDoublequat () const
 Read-only access to the quaternion representing the 3D rotation.
 
mrpt::math::CArrayDouble< 3 > & xyz ()
 Read/Write access to the translation vector in R^3.
 
const mrpt::math::CArrayDouble< 3 > & xyz () const
 Read-only access to the translation vector in R^3.
 
 CPose3DQuat ()
 Default constructor, initialize translation to zeros and quaternion to no rotation.
 
 CPose3DQuat (mrpt::math::TConstructorFlags_Quaternions)
 Constructor which left all the quaternion members un-initialized, for use when speed is critical; Use UNINITIALIZED_POSE as argument to this constructor.
 
 CPose3DQuat (TConstructorFlags_Poses)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
 CPose3DQuat (const double x, const double y, const double z, const mrpt::math::CQuaternionDouble &q)
 Constructor with initilization of the pose - the quaternion is normalized to make sure it's unitary.
 
 CPose3DQuat (const CPose3D &p)
 Constructor from a CPose3D.
 
 CPose3DQuat (const mrpt::math::TPose3DQuat &p)
 Constructor from lightweight object.
 
 CPose3DQuat (const mrpt::math::CMatrixDouble44 &M)
 Constructor from a 4x4 homogeneous transformation matrix.
 
void getHomogeneousMatrix (mrpt::math::CMatrixDouble44 &out_HM) const
 Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
 
void getAsVector (mrpt::math::CVectorDouble &v) const
 Returns a 1x7 vector with [x y z qr qx qy qz].
 
void getAsVector (mrpt::math::CArrayDouble< 7 > &v) const
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
void composeFrom (const CPose3DQuat &A, const CPose3DQuat &B)
 Makes $ this = A \oplus B $ this method is slightly more efficient than "this= A + B;" since it avoids the temporary object.
 
void inverseComposeFrom (const CPose3DQuat &A, const CPose3DQuat &B)
 Makes $ this = A \ominus B $ this method is slightly more efficient than "this= A - B;" since it avoids the temporary 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 $ G = this \oplus L $.
 
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 $ L = G \ominus this $.
 
template<class POINT1 , class POINT2 >
void composePoint (const POINT1 &L, POINT2 &G) const
 Computes the 3D point G such as $ G = this \oplus L $.
 
template<class POINT1 , class POINT2 >
void inverseComposePoint (const POINT1 &G, POINT2 &L) const
 Computes the 3D point L such as $ L = G \ominus this $.
 
CPoint3D operator+ (const CPoint3D &L) const
 Computes the 3D point G such as $ G = this \oplus L $.
 
mrpt::math::TPoint3D operator+ (const mrpt::math::TPoint3D &L) const
 Computes the 3D point G such as $ G = this \oplus L $.
 
CPoint3D operator- (const CPoint3D &G) const
 Computes the 3D point L such as $ L = G \ominus this $.
 
mrpt::math::TPoint3D operator- (const mrpt::math::TPoint3D &G) const
 Computes the 3D point L such as $ L = G \ominus this $.
 
virtual void operator*= (const double s)
 Scalar multiplication (all x y z qr qx qy qz elements are multiplied by the scalar).
 
CPose3DQuatoperator+= (const CPose3DQuat &b)
 Make $ this = this \oplus b $

 
CPose3DQuat operator+ (const CPose3DQuat &p) const
 Return the composed pose $ ret = this \oplus p $

 
CPose3DQuatoperator-= (const CPose3DQuat &b)
 Make $ this = this \ominus b $

 
CPose3DQuat operator- (const CPose3DQuat &p) const
 Return the composed pose $ ret = this \ominus p $

 
void inverse ()
 Convert this pose into its inverse, saving the result in itself.
 
void asString (std::string &s) const
 Returns a human-readable textual representation of the object (eg: "[x y z qr qx qy qz]", angles in degrees.)
 
std::string asString () const
 
void fromString (const std::string &s)
 Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8 1 0 0 0]" )
 
const double & operator[] (unsigned int i) const
 Read only [] operator.
 
double & operator[] (unsigned int i)
 Read/write [] operator.
 
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.
 
const type_valuegetPoseMean () const
 
type_valuegetPoseMean ()
 
void setToNaN () MRPT_OVERRIDE
 Set all data fields to quiet NaN.
 

Static Public Member Functions

static bool is_3D ()
 
static bool is_PDF ()
 

Public Attributes

mrpt::math::CArrayDouble< 3 > m_coords
 The translation vector [x,y,z].
 
mrpt::math::CQuaternionDouble m_quat
 The quaternion.
 

Protected Member Functions

CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const MRPT_OVERRIDE
 
void readFromStream (mrpt::utils::CStream &in, int version) MRPT_OVERRIDE
 

STL-like methods and typedefs


enum  { static_size = 7 }
 
typedef double value_type
 The type of the elements.
 
typedef double & reference
 
typedef const double & const_reference
 
typedef std::size_t size_type
 
typedef std::ptrdiff_t difference_type
 
typedef std::reverse_iterator< iteratorreverse_iterator
 
typedef std::reverse_iterator< const_iteratorconst_reverse_iterator
 
void assign (const size_t N, const double val)
 
iterator begin ()
 
iterator end ()
 
const_iterator begin () const
 
const_iterator end () const
 
reverse_iterator rbegin ()
 
const_reverse_iterator rbegin () const
 
reverse_iterator rend ()
 
const_reverse_iterator rend () const
 
void swap (CPose3DQuat &o)
 
static size_type size ()
 
static bool empty ()
 
static size_type max_size ()
 
static void resize (const size_t n)
 

RTTI stuff <br>

typedef CPose3DQuatPtr SmartPtr
 
static mrpt::utils::CLASSINIT _init_CPose3DQuat
 
static mrpt::utils::TRuntimeClassId classCPose3DQuat
 
static const mrpt::utils::TRuntimeClassIdclassinfo
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const MRPT_OVERRIDE
 
virtual mrpt::utils::CObjectduplicate () const MRPT_OVERRIDE
 
static mrpt::utils::CObjectCreateObject ()
 
static CPose3DQuatPtr Create ()
 
double x () const
 Common members of all points & poses classes.
 
double & x ()
 
void x (const double v)
 
double y () const
 
double & y ()
 
void y (const double v)
 
void x_incr (const double v)
 
void y_incr (const double v)
 
template<class OTHERCLASS >
double sqrDistanceTo (const CPoseOrPoint< OTHERCLASS > &b) const
 Returns the squared euclidean distance to another pose/point:
 
template<class OTHERCLASS >
double distanceTo (const CPoseOrPoint< OTHERCLASS > &b) const
 Returns the Euclidean distance to another pose/point:
 
double distanceTo (const mrpt::math::TPoint3D &b) const
 Returns the euclidean distance to a 3D point:
 
double distance2DToSquare (double ax, double ay) const
 Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
 
double distance3DToSquare (double ax, double ay, double az) const
 Returns the squared 3D distance from this pose/point to a 3D point.
 
double distance2DTo (double ax, double ay) const
 Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
 
double distance3DTo (double ax, double ay, double az) const
 Returns the 3D distance from this pose/point to a 3D point.
 
double norm () const
 Returns the euclidean norm of vector: $ ||\mathbf{x}|| = \sqrt{x^2+y^2+z^2} $.
 
mrpt::math::CVectorDouble getAsVectorVal () const
 Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation)
 
mrpt::math::CMatrixDouble44 getHomogeneousMatrixVal () const
 Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
 
void getInverseHomogeneousMatrix (mrpt::math::CMatrixDouble44 &out_HM) const
 Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose.
 
mrpt::math::CMatrixDouble44 getInverseHomogeneousMatrix () const
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
 
static bool is3DPoseOrPoint ()
 Return true for poses or points with a Z component, false otherwise.
 

Member Typedef Documentation

◆ const_reference

Definition at line 258 of file CPose3DQuat.h.

◆ const_reverse_iterator

Definition at line 411 of file CPose3DQuat.h.

◆ difference_type

Definition at line 260 of file CPose3DQuat.h.

◆ mrpt_autotype

See ops_containers.h.

Definition at line 430 of file CPose3DQuat.h.

◆ reference

Definition at line 257 of file CPose3DQuat.h.

◆ reverse_iterator

typedef std::reverse_iterator<iterator> mrpt::poses::CPose3DQuat::reverse_iterator

Definition at line 410 of file CPose3DQuat.h.

◆ size_type

Definition at line 259 of file CPose3DQuat.h.

◆ SmartPtr

A typedef for the associated smart pointer

Definition at line 44 of file CPose3DQuat.h.

◆ type_value

Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses.

Definition at line 244 of file CPose3DQuat.h.

◆ value_type

The type of the elements.

Definition at line 256 of file CPose3DQuat.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
is_3D_val 

Definition at line 245 of file CPose3DQuat.h.

◆ anonymous enum

anonymous enum
Enumerator
rotation_dimensions 

Definition at line 247 of file CPose3DQuat.h.

◆ anonymous enum

anonymous enum
Enumerator
is_PDF_val 

Definition at line 248 of file CPose3DQuat.h.

◆ anonymous enum

anonymous enum
Enumerator
static_size 

Definition at line 263 of file CPose3DQuat.h.

Constructor & Destructor Documentation

◆ CPose3DQuat() [1/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( )
inline

Default constructor, initialize translation to zeros and quaternion to no rotation.

Definition at line 63 of file CPose3DQuat.h.

◆ CPose3DQuat() [2/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( mrpt::math::TConstructorFlags_Quaternions  )
inline

Constructor which left all the quaternion members un-initialized, for use when speed is critical; Use UNINITIALIZED_POSE as argument to this constructor.

Definition at line 66 of file CPose3DQuat.h.

◆ CPose3DQuat() [3/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( TConstructorFlags_Poses  )
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 68 of file CPose3DQuat.h.

◆ CPose3DQuat() [4/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( const double  x,
const double  y,
const double  z,
const mrpt::math::CQuaternionDouble q 
)
inline

Constructor with initilization of the pose - the quaternion is normalized to make sure it's unitary.

Definition at line 71 of file CPose3DQuat.h.

References mrpt::math::CQuaternion< T >::normalize().

◆ CPose3DQuat() [5/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( const CPose3D p)
explicit

Constructor from a CPose3D.

◆ CPose3DQuat() [6/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( const mrpt::math::TPose3DQuat p)
inline

Constructor from lightweight object.

Definition at line 77 of file CPose3DQuat.h.

References mrpt::math::TPose3DQuat::x, mrpt::math::TPose3DQuat::y, and mrpt::math::TPose3DQuat::z.

◆ CPose3DQuat() [7/7]

mrpt::poses::CPose3DQuat::CPose3DQuat ( const mrpt::math::CMatrixDouble44 M)
explicit

Constructor from a 4x4 homogeneous transformation matrix.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId * mrpt::poses::CPose3DQuat::_GetBaseClass ( )
staticprotected

◆ assign()

void mrpt::poses::CPose3DQuat::assign ( const size_t  N,
const double  val 
)
inline

Definition at line 269 of file CPose3DQuat.h.

◆ asString() [1/2]

std::string mrpt::poses::CPose3DQuat::asString ( ) const
inline

Definition at line 183 of file CPose3DQuat.h.

References asString().

Referenced by asString().

◆ asString() [2/2]

void mrpt::poses::CPose3DQuat::asString ( std::string &  s) const
inline

Returns a human-readable textual representation of the object (eg: "[x y z qr qx qy qz]", angles in degrees.)

See also
fromString

Definition at line 182 of file CPose3DQuat.h.

References mrpt::format().

◆ begin() [1/2]

iterator mrpt::poses::CPose3DQuat::begin ( )
inline

Definition at line 412 of file CPose3DQuat.h.

◆ begin() [2/2]

const_iterator mrpt::poses::CPose3DQuat::begin ( ) const
inline

Definition at line 414 of file CPose3DQuat.h.

◆ composeFrom()

void mrpt::poses::CPose3DQuat::composeFrom ( const CPose3DQuat A,
const CPose3DQuat B 
)

Makes $ this = A \oplus B $ this method is slightly more efficient than "this= A + B;" since it avoids the temporary object.

Note
A or B can be "this" without problems.
See also
inverseComposeFrom, composePoint

Referenced by operator+().

◆ composePoint() [1/2]

void mrpt::poses::CPose3DQuat::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 $ G = this \oplus L $.

See also
composeFrom, inverseComposePoint

◆ composePoint() [2/2]

template<class POINT1 , class POINT2 >
void mrpt::poses::CPose3DQuat::composePoint ( const POINT1 &  L,
POINT2 &  G 
) const
inline

Computes the 3D point G such as $ G = this \oplus L $.

POINT1 and POINT1 can be anything supporing [0],[1],[2].

See also
composePoint

Definition at line 125 of file CPose3DQuat.h.

References composePoint().

Referenced by composePoint().

◆ Create()

static CPose3DQuatPtr mrpt::poses::CPose3DQuat::Create ( )
static

◆ CreateObject()

static mrpt::utils::CObject * mrpt::poses::CPose3DQuat::CreateObject ( )
static

◆ distance2DTo()

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance2DTo ( double  ax,
double  ay 
) const
inlineinherited

Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).

Definition at line 165 of file CPoseOrPoint.h.

References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance2DToSquare().

◆ distance2DToSquare()

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance2DToSquare ( double  ax,
double  ay 
) const
inlineinherited

Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists).

Definition at line 156 of file CPoseOrPoint.h.

References mrpt::utils::square(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().

Referenced by mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance2DTo().

◆ distance3DTo()

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance3DTo ( double  ax,
double  ay,
double  az 
) const
inlineinherited

Returns the 3D distance from this pose/point to a 3D point.

Definition at line 168 of file CPoseOrPoint.h.

References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance3DToSquare().

Referenced by mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo().

◆ distance3DToSquare()

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance3DToSquare ( double  ax,
double  ay,
double  az 
) const
inlineinherited

◆ distanceTo() [1/2]

template<class DERIVEDCLASS >
template<class OTHERCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo ( const CPoseOrPoint< OTHERCLASS > &  b) const
inlineinherited

Returns the Euclidean distance to another pose/point:

Definition at line 150 of file CPoseOrPoint.h.

References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::sqrDistanceTo().

◆ distanceTo() [2/2]

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo ( const mrpt::math::TPoint3D b) const
inlineinherited

Returns the euclidean distance to a 3D point:

Definition at line 171 of file CPoseOrPoint.h.

References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distance3DTo(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.

◆ duplicate()

virtual mrpt::utils::CObject * mrpt::poses::CPose3DQuat::duplicate ( ) const
virtual

◆ empty()

static bool mrpt::poses::CPose3DQuat::empty ( )
inlinestatic

Definition at line 265 of file CPose3DQuat.h.

◆ end() [1/2]

iterator mrpt::poses::CPose3DQuat::end ( )
inline

Definition at line 413 of file CPose3DQuat.h.

References static_size.

◆ end() [2/2]

const_iterator mrpt::poses::CPose3DQuat::end ( ) const
inline

Definition at line 415 of file CPose3DQuat.h.

References static_size.

◆ fromString()

void mrpt::poses::CPose3DQuat::fromString ( const std::string &  s)
inline

Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8 1 0 0 0]" )

See also
asString
Exceptions
std::exceptionOn invalid format

Definition at line 189 of file CPose3DQuat.h.

References ASSERTMSG_, mrpt::math::size(), and THROW_EXCEPTION.

◆ getAsVector() [1/2]

void mrpt::poses::CPose3DQuat::getAsVector ( mrpt::math::CArrayDouble< 7 > &  v) const
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 91 of file CPose3DQuat.h.

◆ getAsVector() [2/2]

void mrpt::poses::CPose3DQuat::getAsVector ( mrpt::math::CVectorDouble v) const

Returns a 1x7 vector with [x y z qr qx qy qz].

◆ getAsVectorVal()

template<class DERIVEDCLASS >
mrpt::math::CVectorDouble mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getAsVectorVal ( ) const
inlineinherited

Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation)

Definition at line 181 of file CPoseOrPoint.h.

◆ getHomogeneousMatrix()

void mrpt::poses::CPose3DQuat::getHomogeneousMatrix ( mrpt::math::CMatrixDouble44 out_HM) const

Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).

See also
getInverseHomogeneousMatrix

◆ getHomogeneousMatrixVal()

template<class DERIVEDCLASS >
mrpt::math::CMatrixDouble44 mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getHomogeneousMatrixVal ( ) const
inlineinherited

Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).

See also
getInverseHomogeneousMatrix

Definition at line 191 of file CPoseOrPoint.h.

References mrpt::math::UNINITIALIZED_MATRIX.

◆ getInverseHomogeneousMatrix() [1/2]

template<class DERIVEDCLASS >
mrpt::math::CMatrixDouble44 mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getInverseHomogeneousMatrix ( ) const
inlineinherited

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 208 of file CPoseOrPoint.h.

References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getInverseHomogeneousMatrix(), and mrpt::math::UNINITIALIZED_MATRIX.

Referenced by mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getInverseHomogeneousMatrix().

◆ getInverseHomogeneousMatrix() [2/2]

template<class DERIVEDCLASS >
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getInverseHomogeneousMatrix ( mrpt::math::CMatrixDouble44 out_HM) const
inlineinherited

Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose.

See also
getHomogeneousMatrix

Definition at line 201 of file CPoseOrPoint.h.

References mrpt::math::homogeneousMatrixInverse().

◆ getPoseMean() [1/2]

type_value & mrpt::poses::CPose3DQuat::getPoseMean ( )
inline

Definition at line 252 of file CPose3DQuat.h.

◆ getPoseMean() [2/2]

const type_value & mrpt::poses::CPose3DQuat::getPoseMean ( ) const
inline

Definition at line 251 of file CPose3DQuat.h.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId * mrpt::poses::CPose3DQuat::GetRuntimeClass ( ) const
virtual

◆ inverse()

void mrpt::poses::CPose3DQuat::inverse ( )

Convert this pose into its inverse, saving the result in itself.

See also
operator-

◆ inverseComposeFrom()

void mrpt::poses::CPose3DQuat::inverseComposeFrom ( const CPose3DQuat A,
const CPose3DQuat B 
)

Makes $ this = A \ominus B $ this method is slightly more efficient than "this= A - B;" since it avoids the temporary object.

Note
A or B can be "this" without problems.
See also
composeFrom, composePoint

Referenced by operator-().

◆ inverseComposePoint() [1/2]

void mrpt::poses::CPose3DQuat::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 $ L = G \ominus this $.

See also
composePoint, composeFrom

◆ inverseComposePoint() [2/2]

template<class POINT1 , class POINT2 >
void mrpt::poses::CPose3DQuat::inverseComposePoint ( const POINT1 &  G,
POINT2 &  L 
) const
inline

Computes the 3D point L such as $ L = G \ominus this $.

See also
inverseComposePoint

Definition at line 128 of file CPose3DQuat.h.

References inverseComposePoint().

Referenced by inverseComposePoint().

◆ is3DPoseOrPoint()

template<class DERIVEDCLASS >
static bool mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::is3DPoseOrPoint ( )
inlinestaticinherited

◆ is_3D()

static bool mrpt::poses::CPose3DQuat::is_3D ( )
inlinestatic

Definition at line 246 of file CPose3DQuat.h.

◆ is_PDF()

static bool mrpt::poses::CPose3DQuat::is_PDF ( )
inlinestatic

Definition at line 249 of file CPose3DQuat.h.

◆ max_size()

static size_type mrpt::poses::CPose3DQuat::max_size ( )
inlinestatic

Definition at line 266 of file CPose3DQuat.h.

References static_size.

◆ norm()

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::norm ( ) const
inlineinherited

◆ operator*=()

virtual void mrpt::poses::CPose3DQuat::operator*= ( const double  s)
virtual

Scalar multiplication (all x y z qr qx qy qz elements are multiplied by the scalar).

◆ operator+() [1/3]

CPoint3D mrpt::poses::CPose3DQuat::operator+ ( const CPoint3D L) const
inline

Computes the 3D point G such as $ G = this \oplus L $.

See also
composePoint

Definition at line 131 of file CPose3DQuat.h.

◆ operator+() [2/3]

CPose3DQuat mrpt::poses::CPose3DQuat::operator+ ( const CPose3DQuat p) const
inline

Return the composed pose $ ret = this \oplus p $

Definition at line 154 of file CPose3DQuat.h.

References composeFrom().

◆ operator+() [3/3]

mrpt::math::TPoint3D mrpt::poses::CPose3DQuat::operator+ ( const mrpt::math::TPoint3D L) const
inline

Computes the 3D point G such as $ G = this \oplus L $.

See also
composePoint

Definition at line 134 of file CPose3DQuat.h.

◆ operator+=()

CPose3DQuat & mrpt::poses::CPose3DQuat::operator+= ( const CPose3DQuat b)
inline

Make $ this = this \oplus b $

Definition at line 147 of file CPose3DQuat.h.

◆ operator-() [1/3]

CPoint3D mrpt::poses::CPose3DQuat::operator- ( const CPoint3D G) const
inline

Computes the 3D point L such as $ L = G \ominus this $.

See also
inverseComposePoint

Definition at line 137 of file CPose3DQuat.h.

◆ operator-() [2/3]

CPose3DQuat mrpt::poses::CPose3DQuat::operator- ( const CPose3DQuat p) const
inline

Return the composed pose $ ret = this \ominus p $

Definition at line 169 of file CPose3DQuat.h.

References inverseComposeFrom().

◆ operator-() [3/3]

mrpt::math::TPoint3D mrpt::poses::CPose3DQuat::operator- ( const mrpt::math::TPoint3D G) const
inline

Computes the 3D point L such as $ L = G \ominus this $.

See also
inverseComposePoint

Definition at line 140 of file CPose3DQuat.h.

◆ operator-=()

CPose3DQuat & mrpt::poses::CPose3DQuat::operator-= ( const CPose3DQuat b)
inline

Make $ this = this \ominus b $

Definition at line 162 of file CPose3DQuat.h.

◆ operator[]() [1/2]

double & mrpt::poses::CPose3DQuat::operator[] ( unsigned int  i)
inline

Read/write [] operator.

Definition at line 214 of file CPose3DQuat.h.

◆ operator[]() [2/2]

const double & mrpt::poses::CPose3DQuat::operator[] ( unsigned int  i) const
inline

Read only [] operator.

Definition at line 198 of file CPose3DQuat.h.

◆ quat() [1/2]

mrpt::math::CQuaternionDouble & mrpt::poses::CPose3DQuat::quat ( )
inline

Read/Write access to the quaternion representing the 3D rotation.

Definition at line 52 of file CPose3DQuat.h.

◆ quat() [2/2]

const mrpt::math::CQuaternionDouble & mrpt::poses::CPose3DQuat::quat ( ) const
inline

Read-only access to the quaternion representing the 3D rotation.

Definition at line 54 of file CPose3DQuat.h.

◆ rbegin() [1/2]

reverse_iterator mrpt::poses::CPose3DQuat::rbegin ( )
inline

Definition at line 416 of file CPose3DQuat.h.

References end().

◆ rbegin() [2/2]

const_reverse_iterator mrpt::poses::CPose3DQuat::rbegin ( ) const
inline

Definition at line 417 of file CPose3DQuat.h.

References end().

◆ readFromStream()

void mrpt::poses::CPose3DQuat::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protected

◆ rend() [1/2]

reverse_iterator mrpt::poses::CPose3DQuat::rend ( )
inline

Definition at line 418 of file CPose3DQuat.h.

References begin().

◆ rend() [2/2]

const_reverse_iterator mrpt::poses::CPose3DQuat::rend ( ) const
inline

Definition at line 419 of file CPose3DQuat.h.

References begin().

◆ resize()

static void mrpt::poses::CPose3DQuat::resize ( const size_t  n)
inlinestatic

Definition at line 267 of file CPose3DQuat.h.

References mrpt::format(), and static_size.

◆ setToNaN()

void mrpt::poses::CPose3DQuat::setToNaN ( )
virtual

Set all data fields to quiet NaN.

Implements mrpt::poses::CPoseOrPoint< DERIVEDCLASS >.

◆ size()

static size_type mrpt::poses::CPose3DQuat::size ( )
inlinestatic

Definition at line 264 of file CPose3DQuat.h.

References static_size.

◆ sphericalCoordinates()

void mrpt::poses::CPose3DQuat::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.

For the coordinate system see the top of this page. If the matrix pointers are not NULL, the Jacobians will be also computed for the range-yaw-pitch variables wrt the passed 3D point and this 7D pose.

◆ sqrDistanceTo()

template<class DERIVEDCLASS >
template<class OTHERCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::sqrDistanceTo ( const CPoseOrPoint< OTHERCLASS > &  b) const
inlineinherited

◆ swap()

void mrpt::poses::CPose3DQuat::swap ( CPose3DQuat o)
inline

Definition at line 422 of file CPose3DQuat.h.

References m_coords, and m_quat.

◆ writeToStream()

void mrpt::poses::CPose3DQuat::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protected

◆ x() [1/3]

template<class DERIVEDCLASS >
double & mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x ( )
inlineinherited

Definition at line 116 of file CPoseOrPoint.h.

◆ x() [2/3]

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x ( ) const
inlineinherited

◆ x() [3/3]

template<class DERIVEDCLASS >
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x ( const double  v)
inlineinherited
Parameters
vSet X coord.

Definition at line 119 of file CPoseOrPoint.h.

◆ x_incr()

template<class DERIVEDCLASS >
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x_incr ( const double  v)
inlineinherited
Parameters
vX+=v

Definition at line 122 of file CPoseOrPoint.h.

◆ xyz() [1/2]

mrpt::math::CArrayDouble< 3 > & mrpt::poses::CPose3DQuat::xyz ( )
inline

Read/Write access to the translation vector in R^3.

Definition at line 57 of file CPose3DQuat.h.

◆ xyz() [2/2]

const mrpt::math::CArrayDouble< 3 > & mrpt::poses::CPose3DQuat::xyz ( ) const
inline

Read-only access to the translation vector in R^3.

Definition at line 59 of file CPose3DQuat.h.

◆ y() [1/3]

template<class DERIVEDCLASS >
double & mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y ( )
inlineinherited

Definition at line 117 of file CPoseOrPoint.h.

◆ y() [2/3]

template<class DERIVEDCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y ( ) const
inlineinherited

◆ y() [3/3]

template<class DERIVEDCLASS >
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y ( const double  v)
inlineinherited
Parameters
vSet Y coord.

Definition at line 120 of file CPoseOrPoint.h.

◆ y_incr()

template<class DERIVEDCLASS >
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y_incr ( const double  v)
inlineinherited
Parameters
vY+=v

Definition at line 123 of file CPoseOrPoint.h.

Member Data Documentation

◆ _init_CPose3DQuat

mrpt::utils::CLASSINIT mrpt::poses::CPose3DQuat::_init_CPose3DQuat
staticprotected

Definition at line 44 of file CPose3DQuat.h.

◆ classCPose3DQuat

mrpt::utils::TRuntimeClassId mrpt::poses::CPose3DQuat::classCPose3DQuat
static

Definition at line 44 of file CPose3DQuat.h.

◆ classinfo

const mrpt::utils::TRuntimeClassId* mrpt::poses::CPose3DQuat::classinfo
static

Definition at line 44 of file CPose3DQuat.h.

◆ m_coords

mrpt::math::CArrayDouble<3> mrpt::poses::CPose3DQuat::m_coords

The translation vector [x,y,z].

Definition at line 47 of file CPose3DQuat.h.

Referenced by swap().

◆ m_quat

mrpt::math::CQuaternionDouble mrpt::poses::CPose3DQuat::m_quat

The quaternion.

Definition at line 48 of file CPose3DQuat.h.

Referenced by swap().




Page generated by Doxygen 1.9.6 for MRPT 1.4.0 SVN: at Wed Feb 15 01:46:32 UTC 2023