base
|
#include <TransformWithCovariance.hpp>
Public Types | |
typedef base::Matrix6d | Covariance |
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) |
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.
|
inline |
|
inlineexplicit |
|
inline |
|
inline |
|
inline |
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.
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
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.
|
staticprotected |
|
staticprotected |
|
staticprotected |
|
staticprotected |
|
staticprotected |
|
staticprotected |
|
staticprotected |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlinestatic |
|
inline |
|
inline |
TransformWithCovariance base::TransformWithCovariance::inverse | ( | ) | const |
TransformWithCovariance base::TransformWithCovariance::operator* | ( | const TransformWithCovariance & | trans | ) | const |
alias for the composition of two transforms
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.
|
staticprotected |
|
staticprotected |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlinestaticprotected |
|
staticprotected |
|
friend |
Default std::cout function
cout the 6D pose vector (translation and scaled axis orientation) with its associated covariance matrix
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.
base::Quaterniond base::TransformWithCovariance::orientation |
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.