MIRA
|
Specialization of RigidTransformCov for 3 dimensions.
More...
#include <transform/RigidTransform.h>
Public Types | |
typedef Eigen::Matrix< T, CovarianceDim, CovarianceDim > | CovMatrixType |
The type of the matrix representing the covariance of the transformation. More... | |
typedef Eigen::Matrix< T, EulerCovarianceDim, EulerCovarianceDim > | YawPitchRollCovMatrixType |
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, HDim > | MatrixType |
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 |
RigidTransformCov & | operator*= (const RigidTransformCov &other) |
RigidTransformCov & | operator*= (const Base &other) |
T & | x () |
Returns the x-coordinate of the translational part of the transform. More... | |
T | 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... | |
T | 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... | |
T | z () const |
Returns the z-coordinate of the translational part of the transform. More... | |
T | yaw () const |
Returns the yaw angle in rad (This corresponds to phi in a 2D transform). More... | |
T | pitch () const |
Returns the pitch angle in rad. More... | |
T | 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) |
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.
typedef Eigen::Matrix<T,CovarianceDim,CovarianceDim> CovMatrixType |
The type of the matrix representing the covariance of the transformation.
The matrix is 7x7 for 3D transformations.
The type of the matrix representing the euler covariance of the transformation.
The matrix is 6x6 for 3D transformations.
|
inherited |
The used floating point type (float, double, long double)
|
inherited |
Vector type used to represent the translational part (dimension depends on dimensionality of transform).
|
inherited |
Type used to represent the rotational part (Eigen::Rotation2D for 2D transforms, Eigen::Quaternion for 3D transforms)
|
inherited |
Type of the matrix that can describe the full affine transform in homogeneous space.
|
inherited |
|
inline |
|
inline |
Initialization from corresponding RigidTransform (without covariance).
The covariance matrix is set to the null covariance matrix.
|
inline |
Initialization from the translation, rotation as quaternion and the covariance matrix in quaternion space.
|
inline |
Initialization from the translation, rotation as quaternion and the covariance matrix in yaw/pitch/roll angle space.
|
inline |
Initialization from the translation, rotation given as yaw/pitch/roll angles and the covariance matrix in yaw/pitch/roll angle space.
|
inlinestatic |
Returns a "null covariance matrix".
|
inlinestatic |
Returns an "null covariance matrix" witch yaw, pitch, roll rotation representation.
|
inline |
Returns *this casted to U.
|
inline |
Returns covariance matrix where the rotation covariance is represented using yaw, pitch, roll.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlineinherited |
Returns the x-coordinate of the translational part of the transform.
|
inlineinherited |
Returns the x-coordinate of the translational part of the transform.
|
inlineinherited |
Returns the y-coordinate of the translational part of the transform.
|
inlineinherited |
Returns the y-coordinate of the translational part of the transform.
|
inlineinherited |
Returns the z-coordinate of the translational part of the transform.
|
inlineinherited |
Returns the z-coordinate of the translational part of the transform.
|
inlineinherited |
Returns the yaw angle in rad (This corresponds to phi in a 2D transform).
|
inlineinherited |
Returns the pitch angle in rad.
|
inlineinherited |
Returns the roll angle in rad.
|
inlineinherited |
Returns true if this is approximately equal to other, within the precision determined by prec.
|
inlineinherited |
Concatenates this transform with an other transform.
|
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.
|
inlineinherited |
Cast operator that casts the rigid transform into a generic Eigen::Transform object.
|
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.
|
inlineprotectedinherited |
casts this to the actual derived type (see Curiously recurring template pattern)
|
inlineprotectedinherited |
casts this to the actual derived type (see Curiously recurring template pattern)
|
inlinestaticprotectedinherited |
|
friend |
|
friend |
|
friend |
|
friend |
|
static |
Dimension of the covariance matrix.
|
static |
Dimension of the euler covariance matrix.
CovMatrixType cov |
the covariance of the transform as matrix:
|
inherited |
Vector that describes the translational part of the transform.
|
inherited |
The rotational part of the transform.