base
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Protected Member Functions | Friends | List of all members
base::TransformWithCovariance Class Reference

#include <TransformWithCovariance.hpp>

Public Types

typedef base::Matrix6d Covariance
 

Public Member Functions

 TransformWithCovariance ()
 
 TransformWithCovariance (const base::Affine3d &trans)
 
 TransformWithCovariance (const base::Affine3d &trans, const Covariance &cov)
 
 TransformWithCovariance (const base::Position &translation, const base::Quaterniond &orientation)
 
 TransformWithCovariance (const base::Position &translation, const base::Quaterniond &orientation, const Covariance &cov)
 
TransformWithCovariance composition (const TransformWithCovariance &trans) const
 
TransformWithCovariance compositionInv (const TransformWithCovariance &trans) const
 
TransformWithCovariance preCompositionInv (const TransformWithCovariance &trans) const
 
TransformWithCovariance operator* (const TransformWithCovariance &trans) const
 
std::pair< Eigen::Vector3d, Eigen::Matrix3d > composePointWithCovariance (const Eigen::Vector3d &point, const Eigen::Matrix3d &cov) const
 
TransformWithCovariance inverse () const
 
const CovariancegetCovariance () const
 
void setCovariance (const Covariance &cov)
 
const base::Matrix3d getTranslationCov () const
 
void setTranslationCov (const base::Matrix3d &cov)
 
const base::Matrix3d getOrientationCov () const
 
void setOrientationCov (const base::Matrix3d &cov)
 
const base::Affine3d getTransform () const
 
void setTransform (const base::Affine3d &trans)
 
const base::OrientationgetOrientation () const
 
void setOrientation (const base::Orientation &q)
 
bool hasValidTransform () const
 
void invalidateTransform ()
 
bool hasValidCovariance () const
 
void invalidateCovariance ()
 

Static Public Member Functions

static TransformWithCovariance Identity ()
 

Public Attributes

base::Position translation
 
base::Quaterniond orientation
 
Covariance cov
 

Static Protected Member Functions

static Eigen::Quaterniond r_to_q (const Eigen::Vector3d &r)
 
static Eigen::Vector3d q_to_r (const Eigen::Quaterniond &q)
 
static double sign (double v)
 
static Eigen::Matrix< double, 3, 3 > skew_symmetric (const Eigen::Vector3d &r)
 
static Eigen::Matrix< double, 4, 3 > dq_by_dr (const Eigen::Quaterniond &q)
 
static Eigen::Matrix< double, 3, 4 > dr_by_dq (const Eigen::Quaterniond &q)
 
static Eigen::Matrix< double, 4, 4 > dq2q1_by_dq1 (const Eigen::Quaterniond &q2)
 
static Eigen::Matrix< double, 4, 4 > dq2q1_by_dq2 (const Eigen::Quaterniond &q1)
 
static Eigen::Matrix< double, 3, 3 > dr2r1_by_r1 (const Eigen::Quaterniond &q, const Eigen::Quaterniond &q1, const Eigen::Quaterniond &q2)
 
static Eigen::Matrix< double, 3, 3 > dr2r1_by_r2 (const Eigen::Quaterniond &q, const Eigen::Quaterniond &q1, const Eigen::Quaterniond &q2)
 
static Eigen::Matrix< double, 3, 3 > drx_by_dr (const Eigen::Quaterniond &q, const Eigen::Vector3d &x)
 

Friends

std::ostream & operator<< (std::ostream &out, const TransformWithCovariance &trans)
 

Detailed Description

Class which represents a 3D Transformation with associated uncertainty information.

The uncertainty is represented as a 6x6 matrix, which is the covariance matrix of the [r t] representation of the error. Here r is the rotation orientation part expressed as a scaled axis of orientation, and t the translational component.

The uncertainty information is optional. The hasValidCovariance() method can be used to see if uncertainty information is associated with the class.

Member Typedef Documentation

◆ Covariance

Constructor & Destructor Documentation

◆ TransformWithCovariance() [1/5]

base::TransformWithCovariance::TransformWithCovariance ( )
inline

◆ TransformWithCovariance() [2/5]

base::TransformWithCovariance::TransformWithCovariance ( const base::Affine3d trans)
inlineexplicit

◆ TransformWithCovariance() [3/5]

base::TransformWithCovariance::TransformWithCovariance ( const base::Affine3d trans,
const Covariance cov 
)
inline

◆ TransformWithCovariance() [4/5]

base::TransformWithCovariance::TransformWithCovariance ( const base::Position translation,
const base::Quaterniond orientation 
)
inline

◆ TransformWithCovariance() [5/5]

base::TransformWithCovariance::TransformWithCovariance ( const base::Position translation,
const base::Quaterniond orientation,
const Covariance cov 
)
inline

Member Function Documentation

◆ composePointWithCovariance()

std::pair< Eigen::Vector3d, Eigen::Matrix3d > base::TransformWithCovariance::composePointWithCovariance ( const Eigen::Vector3d point,
const Eigen::Matrix3d &  cov 
) const

performs a composition of this transform with a given point with covariance.

◆ composition()

TransformWithCovariance base::TransformWithCovariance::composition ( const TransformWithCovariance trans) const

performs a composition of this transform with the transform given. The result is another transform with result = this * trans

◆ compositionInv()

TransformWithCovariance base::TransformWithCovariance::compositionInv ( const TransformWithCovariance trans) const

performs an inverse composition of two transformations. The result is such that result * trans = this. Note that this is different from calling result = this * inv(trans), in the way the uncertainties are handled.

◆ dq2q1_by_dq1()

Eigen::Matrix< double, int(4), int(4) > base::TransformWithCovariance::dq2q1_by_dq1 ( const Eigen::Quaterniond q2)
staticprotected

◆ dq2q1_by_dq2()

Eigen::Matrix< double, int(4), int(4) > base::TransformWithCovariance::dq2q1_by_dq2 ( const Eigen::Quaterniond q1)
staticprotected

◆ dq_by_dr()

Eigen::Matrix< double, int(4), int(3) > base::TransformWithCovariance::dq_by_dr ( const Eigen::Quaterniond q)
staticprotected

◆ dr2r1_by_r1()

Eigen::Matrix< double, int(3), int(3) > base::TransformWithCovariance::dr2r1_by_r1 ( const Eigen::Quaterniond q,
const Eigen::Quaterniond q1,
const Eigen::Quaterniond q2 
)
staticprotected

◆ dr2r1_by_r2()

Eigen::Matrix< double, int(3), int(3) > base::TransformWithCovariance::dr2r1_by_r2 ( const Eigen::Quaterniond q,
const Eigen::Quaterniond q1,
const Eigen::Quaterniond q2 
)
staticprotected

◆ dr_by_dq()

Eigen::Matrix< double, int(3), int(4) > base::TransformWithCovariance::dr_by_dq ( const Eigen::Quaterniond q)
staticprotected

◆ drx_by_dr()

Eigen::Matrix< double, int(3), int(3) > base::TransformWithCovariance::drx_by_dr ( const Eigen::Quaterniond q,
const Eigen::Vector3d x 
)
staticprotected

◆ getCovariance()

const Covariance& base::TransformWithCovariance::getCovariance ( ) const
inline

◆ getOrientation()

const base::Orientation& base::TransformWithCovariance::getOrientation ( ) const
inline

◆ getOrientationCov()

const base::Matrix3d base::TransformWithCovariance::getOrientationCov ( ) const
inline

◆ getTransform()

const base::Affine3d base::TransformWithCovariance::getTransform ( ) const
inline

◆ getTranslationCov()

const base::Matrix3d base::TransformWithCovariance::getTranslationCov ( ) const
inline

◆ hasValidCovariance()

bool base::TransformWithCovariance::hasValidCovariance ( ) const
inline
Warning
This method is computationally expensive. Use with care!

◆ hasValidTransform()

bool base::TransformWithCovariance::hasValidTransform ( ) const
inline

◆ Identity()

static TransformWithCovariance base::TransformWithCovariance::Identity ( )
inlinestatic

◆ invalidateCovariance()

void base::TransformWithCovariance::invalidateCovariance ( )
inline

◆ invalidateTransform()

void base::TransformWithCovariance::invalidateTransform ( )
inline

◆ inverse()

TransformWithCovariance base::TransformWithCovariance::inverse ( ) const

◆ operator*()

TransformWithCovariance base::TransformWithCovariance::operator* ( const TransformWithCovariance trans) const

alias for the composition of two transforms

◆ preCompositionInv()

TransformWithCovariance base::TransformWithCovariance::preCompositionInv ( const TransformWithCovariance trans) const

Same as compositionInv, just that the result is such that trans * result = this. Note that this is different from calling result = inv(trans) * this, in the way the uncertainties are handled.

◆ q_to_r()

Eigen::Vector3d base::TransformWithCovariance::q_to_r ( const Eigen::Quaterniond q)
staticprotected

◆ r_to_q()

Eigen::Quaterniond base::TransformWithCovariance::r_to_q ( const Eigen::Vector3d r)
staticprotected

◆ setCovariance()

void base::TransformWithCovariance::setCovariance ( const Covariance cov)
inline

◆ setOrientation()

void base::TransformWithCovariance::setOrientation ( const base::Orientation q)
inline

◆ setOrientationCov()

void base::TransformWithCovariance::setOrientationCov ( const base::Matrix3d cov)
inline

◆ setTransform()

void base::TransformWithCovariance::setTransform ( const base::Affine3d trans)
inline

◆ setTranslationCov()

void base::TransformWithCovariance::setTranslationCov ( const base::Matrix3d cov)
inline

◆ sign()

double base::TransformWithCovariance::sign ( double  v)
inlinestaticprotected

◆ skew_symmetric()

Eigen::Matrix< double, int(3), int(3) > base::TransformWithCovariance::skew_symmetric ( const Eigen::Vector3d r)
staticprotected

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  out,
const TransformWithCovariance trans 
)
friend

Default std::cout function

cout the 6D pose vector (translation and scaled axis orientation) with its associated covariance matrix

Member Data Documentation

◆ cov

Covariance base::TransformWithCovariance::cov

The uncertainty is represented as a 6x6 matrix, which is the covariance matrix of the [translation orientation] representation of the error.

◆ orientation

base::Quaterniond base::TransformWithCovariance::orientation

◆ translation

base::Position base::TransformWithCovariance::translation

The transformation is represented 6D vector [translation orientation] Here orientation is the rotational part expressed as a quaternion orientation, and t the translational component.


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