MIRA
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Static Protected Member Functions | Friends | List of all members
RigidTransformCov< T, 3 > Class Template Reference


Specialization of RigidTransformCov for 3 dimensions. More...

#include <transform/RigidTransform.h>

Inheritance diagram for RigidTransformCov< T, 3 >:
Inheritance graph
[legend]

Public Types

typedef Eigen::Matrix< T, CovarianceDim, CovarianceDimCovMatrixType
 The type of the matrix representing the covariance of the transformation. More...
 
typedef Eigen::Matrix< T, EulerCovarianceDim, EulerCovarianceDimYawPitchRollCovMatrixType
 The type of the matrix representing the euler covariance of the transformation. More...
 
enum  
 
typedef T Type
 The used floating point type (float, double, long double) More...
 
typedef Eigen::Matrix< T, D, 1 > TranslationType
 Vector type used to represent the translational part (dimension depends on dimensionality of transform). More...
 
typedef Eigen::Quaternion< T > RotationType
 Type used to represent the rotational part (Eigen::Rotation2D for 2D transforms, Eigen::Quaternion for 3D transforms) More...
 
typedef Eigen::Matrix< T, HDim, HDimMatrixType
 Type of the matrix that can describe the full affine transform in homogeneous space. More...
 

Public Member Functions

 RigidTransformCov ()
 
 RigidTransformCov (const Base &transform)
 Initialization from corresponding RigidTransform (without covariance). More...
 
 RigidTransformCov (const Eigen::Matrix< T, 3, 1 > &translation, const Eigen::Quaternion< T > &rotation, const CovMatrixType &covariance)
 Initialization from the translation, rotation as quaternion and the covariance matrix in quaternion space. More...
 
 RigidTransformCov (const Eigen::Matrix< T, 3, 1 > &translation, const Eigen::Quaternion< T > &rotation, const YawPitchRollCovMatrixType &yawPitchRollCov)
 Initialization from the translation, rotation as quaternion and the covariance matrix in yaw/pitch/roll angle space. More...
 
 RigidTransformCov (T x, T y, T z, T yaw, T pitch, T roll, const YawPitchRollCovMatrixType &yawPitchRollCov)
 Initialization from the translation, rotation given as yaw/pitch/roll angles and the covariance matrix in yaw/pitch/roll angle space. More...
 
template<typename U >
RigidTransformCov< U, 3 > cast () const
 Returns *this casted to U. More...
 
YawPitchRollCovMatrixType getYawPitchRollCov () const
 Returns covariance matrix where the rotation covariance is represented using yaw, pitch, roll. More...
 
template<typename Derived >
void reflect (BinarySerializer< Derived > &r)
 
template<typename Derived >
void reflect (BinaryDeserializer< Derived > &r)
 
template<typename Reflector >
void reflectRead (Reflector &r)
 
template<typename Reflector >
void reflectWrite (Reflector &r)
 
RigidTransformCov inverse () const
 
RigidTransformCovoperator*= (const RigidTransformCov &other)
 
RigidTransformCovoperator*= (const Base &other)
 
T & x ()
 Returns the x-coordinate of the translational part of the transform. More...
 
x () const
 Returns the x-coordinate of the translational part of the transform. More...
 
T & y ()
 Returns the y-coordinate of the translational part of the transform. More...
 
y () const
 Returns the y-coordinate of the translational part of the transform. More...
 
T & z ()
 Returns the z-coordinate of the translational part of the transform. More...
 
z () const
 Returns the z-coordinate of the translational part of the transform. More...
 
yaw () const
 Returns the yaw angle in rad (This corresponds to phi in a 2D transform). More...
 
pitch () const
 Returns the pitch angle in rad. More...
 
roll () const
 Returns the roll angle in rad. More...
 
bool isApprox (const RigidTransformBase &other, T prec=std::numeric_limits< T >::epsilon()) const
 Returns true if this is approximately equal to other, within the precision determined by prec. More...
 
RigidTransform< T, 3 > & operator*= (const RigidTransformBase &other)
 Concatenates this transform with an other transform. More...
 
ei_rigidtransform_product_impl< D, RigidTransform< T, 3 >, OtherDerived >::TResult operator* (const Eigen::MatrixBase< OtherDerived > &other) const
 Apply the transformation to an Eigen matrix. More...
 
 operator Eigen::Transform< T, D, Eigen::Isometry > ()
 Cast operator that casts the rigid transform into a generic Eigen::Transform object. More...
 
MatrixType getMatrix () const
 Computes and returns the matrix that describes the affine transformation in homogeneous space. More...
 

Static Public Member Functions

static CovMatrixType nullCov ()
 Returns a "null covariance matrix". More...
 
static YawPitchRollCovMatrixType nullYawPitchRollCov ()
 Returns an "null covariance matrix" witch yaw, pitch, roll rotation representation. More...
 

Public Attributes

CovMatrixType cov
 the covariance of the transform as matrix: More...
 
TranslationType t
 Vector that describes the translational part of the transform. More...
 
RotationType r
 The rotational part of the transform. More...
 

Static Public Attributes

static const int CovarianceDim = 7
 Dimension of the covariance matrix. More...
 
static const int EulerCovarianceDim = 6
 Dimension of the euler covariance matrix. More...
 

Protected Member Functions

RigidTransform< T, 3 > * This ()
 casts this to the actual derived type (see Curiously recurring template pattern) More...
 
const RigidTransform< T, 3 > * This () const
 casts this to the actual derived type (see Curiously recurring template pattern) More...
 

Static Protected Member Functions

static RigidTransform< T, 3 > mul (const RigidTransformBase &a, const RigidTransformBase &b)
 

Friends

MIRA_SPLIT_REFLECT_MEMBER friend std::ostream & operator<< (std::ostream &os, const RigidTransformCov &tf)
 
RigidTransformCov operator* (const RigidTransformCov &a, const RigidTransformCov &b)
 
RigidTransformCov operator* (const RigidTransformCov &a, const Base &b)
 
RigidTransformCov operator* (const Base &a, const RigidTransformCov &b)
 

Detailed Description

template<typename T>
class mira::RigidTransformCov< T, 3 >


Specialization of RigidTransformCov for 3 dimensions.

The covariance matrix has the following representation:

           x          y         z         qw         qx         qy         qz
       .......................................................................
     x : var(x)   ,cov(x,y) ,cov(x,z) ,cov(x,qw) ,cov(x,qx) ,cov(x,qy) ,cov(x,qz)
     y : cov(y,x) ,var(y)   ,cov(y,z) ,            ....
     z :                               ...
    qw :                               ...
    qx :                               ...
    qy :                               ...
    qz :                               ...                              ,var(qz)
* 

This class represents an affine transformation that supports a translation followed by a rotation (a so called rigid transform). In comparison to the RigidTransform class this class also takes the uncertainty of a transform into account (e.g. the uncertainty of a pose, etc). The uncertainty is modeled as normal distribution and is expressed by its covariance matrix.

A rigid transformation is one in which the pre-image and the image both has the exact same size and shape.

These limitations are sufficient for our purposes (rigid body transform, transformation of coordinate frames, etc) and allows efficient computation of the operations. Moreover, the limitation to rigid transforms allows efficient interpolation between two different transformations.

Member Typedef Documentation

◆ CovMatrixType

The type of the matrix representing the covariance of the transformation.

The matrix is 7x7 for 3D transformations.

◆ YawPitchRollCovMatrixType

The type of the matrix representing the euler covariance of the transformation.

The matrix is 6x6 for 3D transformations.

◆ Type

typedef T Type
inherited

The used floating point type (float, double, long double)

◆ TranslationType

typedef Eigen::Matrix<T,D,1> TranslationType
inherited

Vector type used to represent the translational part (dimension depends on dimensionality of transform).

◆ RotationType

typedef Eigen::Quaternion< T > RotationType
inherited

Type used to represent the rotational part (Eigen::Rotation2D for 2D transforms, Eigen::Quaternion for 3D transforms)

◆ MatrixType

typedef Eigen::Matrix<T,HDim,HDim> MatrixType
inherited

Type of the matrix that can describe the full affine transform in homogeneous space.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
inherited

Constructor & Destructor Documentation

◆ RigidTransformCov() [1/5]

RigidTransformCov ( )
inline

◆ RigidTransformCov() [2/5]

RigidTransformCov ( const Base transform)
inline

Initialization from corresponding RigidTransform (without covariance).

The covariance matrix is set to the null covariance matrix.

◆ RigidTransformCov() [3/5]

RigidTransformCov ( const Eigen::Matrix< T, 3, 1 > &  translation,
const Eigen::Quaternion< T > &  rotation,
const CovMatrixType covariance 
)
inline

Initialization from the translation, rotation as quaternion and the covariance matrix in quaternion space.

◆ RigidTransformCov() [4/5]

RigidTransformCov ( const Eigen::Matrix< T, 3, 1 > &  translation,
const Eigen::Quaternion< T > &  rotation,
const YawPitchRollCovMatrixType yawPitchRollCov 
)
inline

Initialization from the translation, rotation as quaternion and the covariance matrix in yaw/pitch/roll angle space.

◆ RigidTransformCov() [5/5]

RigidTransformCov ( x,
y,
z,
yaw,
pitch,
roll,
const YawPitchRollCovMatrixType yawPitchRollCov 
)
inline

Initialization from the translation, rotation given as yaw/pitch/roll angles and the covariance matrix in yaw/pitch/roll angle space.

Member Function Documentation

◆ nullCov()

static CovMatrixType nullCov ( )
inlinestatic

Returns a "null covariance matrix".

◆ nullYawPitchRollCov()

static YawPitchRollCovMatrixType nullYawPitchRollCov ( )
inlinestatic

Returns an "null covariance matrix" witch yaw, pitch, roll rotation representation.

◆ cast()

RigidTransformCov<U,3> cast ( ) const
inline

Returns *this casted to U.

◆ getYawPitchRollCov()

YawPitchRollCovMatrixType getYawPitchRollCov ( ) const
inline

Returns covariance matrix where the rotation covariance is represented using yaw, pitch, roll.

◆ reflect() [1/2]

void reflect ( BinarySerializer< Derived > &  r)
inline

◆ reflect() [2/2]

void reflect ( BinaryDeserializer< Derived > &  r)
inline

◆ reflectRead()

void reflectRead ( Reflector &  r)
inline

◆ reflectWrite()

void reflectWrite ( Reflector &  r)
inline

◆ inverse()

RigidTransformCov inverse ( void  ) const
inline

◆ operator*=() [1/3]

RigidTransformCov& operator*= ( const RigidTransformCov< T, 3 > &  other)
inline

◆ operator*=() [2/3]

RigidTransformCov& operator*= ( const Base other)
inline

◆ x() [1/2]

T& x ( )
inlineinherited

Returns the x-coordinate of the translational part of the transform.

◆ x() [2/2]

T x ( ) const
inlineinherited

Returns the x-coordinate of the translational part of the transform.

◆ y() [1/2]

T& y ( )
inlineinherited

Returns the y-coordinate of the translational part of the transform.

◆ y() [2/2]

T y ( ) const
inlineinherited

Returns the y-coordinate of the translational part of the transform.

◆ z() [1/2]

T& z ( )
inlineinherited

Returns the z-coordinate of the translational part of the transform.

◆ z() [2/2]

T z ( ) const
inlineinherited

Returns the z-coordinate of the translational part of the transform.

◆ yaw()

T yaw ( ) const
inlineinherited

Returns the yaw angle in rad (This corresponds to phi in a 2D transform).

Note
: This method is provided for convenience. It's computation can be quite expensive. Hence, use it with care and use the underlying quaternion instead whenever possible.

◆ pitch()

T pitch ( ) const
inlineinherited

Returns the pitch angle in rad.

Note
: This method is provided for convenience. It's computation can be quite expensive. Hence, use it with care and use the underlying quaternion instead whenever possible.

◆ roll()

T roll ( ) const
inlineinherited

Returns the roll angle in rad.

Note
: This method is provided for convenience. It's computation can be quite expensive. Hence, use it with care and use the underlying quaternion instead whenever possible.

◆ isApprox()

bool isApprox ( const RigidTransformBase< T, 3, Eigen::Quaternion< T >, RigidTransform< T, 3 > > &  other,
prec = std::numeric_limits<T>::epsilon() 
) const
inlineinherited

Returns true if this is approximately equal to other, within the precision determined by prec.

Returns
true if approximately equal, false otherwise

◆ operator*=() [3/3]

RigidTransform< T, 3 > & operator*= ( const RigidTransformBase< T, 3, Eigen::Quaternion< T >, RigidTransform< T, 3 > > &  other)
inlineinherited

Concatenates this transform with an other transform.

◆ operator*()

ei_rigidtransform_product_impl<D, RigidTransform< T, 3 > , OtherDerived>::TResult operator* ( const Eigen::MatrixBase< OtherDerived > &  other) const
inlineinherited

Apply the transformation to an Eigen matrix.

The matrix must be a fixed matrix of the size Dx1 or a dynamic matrix of the same size.

◆ operator Eigen::Transform< T, D, Eigen::Isometry >()

operator Eigen::Transform< T, D, Eigen::Isometry > ( )
inlineinherited

Cast operator that casts the rigid transform into a generic Eigen::Transform object.

◆ getMatrix()

MatrixType getMatrix ( ) const
inlineinherited

Computes and returns the matrix that describes the affine transformation in homogeneous space.

The dimensions of the matrix is 3x3 for 2D transformations and 4x4 for 3D transformations.

◆ This() [1/2]

RigidTransform< T, 3 > * This ( )
inlineprotectedinherited

casts this to the actual derived type (see Curiously recurring template pattern)

◆ This() [2/2]

const RigidTransform< T, 3 > * This ( ) const
inlineprotectedinherited

casts this to the actual derived type (see Curiously recurring template pattern)

◆ mul()

static RigidTransform< T, 3 > mul ( const RigidTransformBase< T, 3, Eigen::Quaternion< T >, RigidTransform< T, 3 > > &  a,
const RigidTransformBase< T, 3, Eigen::Quaternion< T >, RigidTransform< T, 3 > > &  b 
)
inlinestaticprotectedinherited

Friends And Related Function Documentation

◆ operator<<

MIRA_SPLIT_REFLECT_MEMBER friend std::ostream& operator<< ( std::ostream &  os,
const RigidTransformCov< T, 3 > &  tf 
)
friend

◆ operator* [1/3]

RigidTransformCov operator* ( const RigidTransformCov< T, 3 > &  a,
const RigidTransformCov< T, 3 > &  b 
)
friend

◆ operator* [2/3]

RigidTransformCov operator* ( const RigidTransformCov< T, 3 > &  a,
const Base b 
)
friend

◆ operator* [3/3]

RigidTransformCov operator* ( const Base a,
const RigidTransformCov< T, 3 > &  b 
)
friend

Member Data Documentation

◆ CovarianceDim

const int CovarianceDim = 7
static

Dimension of the covariance matrix.

◆ EulerCovarianceDim

const int EulerCovarianceDim = 6
static

Dimension of the euler covariance matrix.

◆ cov

the covariance of the transform as matrix:

◆ t

TranslationType t
inherited

Vector that describes the translational part of the transform.

◆ r

RotationType r
inherited

The rotational part of the transform.


The documentation for this class was generated from the following file: