A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of translation r_AB (represented in frame A) and Quaternion q_AB (as an Eigen Quaternion). see also the RSS'13 / IJRR'14 paper or the Thesis. Follows some of the functionality of the SchweizerMesser library by Paul Furgale, but uses Eigen quaternions underneath.
More...
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | Transformation () |
| Default constructor: initialises a unit transformation. More...
|
|
| Transformation (const Transformation &other) |
| Copy constructor: nothing fancy but takes care of not doing bad stuff with internal caching. More...
|
|
| Transformation (Transformation &&other) |
| Move constructor: nothing fancy but takes care of not doing bad stuff with internal caching. More...
|
|
| Transformation (const Eigen::Vector3d &r_AB, const Eigen::Quaterniond &q_AB) |
| Construct from a translation and quaternion. More...
|
|
| Transformation (const Eigen::Matrix4d &T_AB) |
| Construct from a homogeneous transformation matrix. More...
|
|
| ~Transformation () |
| Trivial destructor. More...
|
|
template<typename Derived_coeffs > |
bool | setCoeffs (const Eigen::MatrixBase< Derived_coeffs > &coeffs) |
| Parameter setting, all 7. More...
|
|
template<typename Derived_coeffs > |
bool | setParameters (const Eigen::MatrixBase< Derived_coeffs > ¶meters) |
| Parameter setting, all 7. More...
|
|
Eigen::Matrix4d | T () const |
| The underlying homogeneous transformation matrix. More...
|
|
const Eigen::Matrix3d & | C () const |
| Returns the rotation matrix (cached). More...
|
|
const Eigen::Map
< Eigen::Vector3d > & | r () const |
| Returns the translation vector r_AB (represented in frame A). More...
|
|
const Eigen::Map
< Eigen::Quaterniond > & | q () const |
| Returns the Quaternion q_AB (as an Eigen Quaternion). More...
|
|
Eigen::Matrix< double, 3, 4 > | T3x4 () const |
| Get the upper 3x4 part of the homogeneous transformation matrix T_AB. More...
|
|
const Eigen::Matrix< double, 7, 1 > & | coeffs () const |
| The coefficients (parameters) as [r_AB,q_AB], q_AB as [x,y,z,w] (Eigen internal convention). More...
|
|
const Eigen::Matrix< double, 7, 1 > & | parameters () const |
| The parameters (coefficients) as [r_AB,q_AB], q_AB as [x,y,z,w] (Eigen internal convention). More...
|
|
const double * | parameterPtr () const |
| Get the parameters — support for ceres. More...
|
|
void | setRandom () |
| Set this to a random transformation. More...
|
|
void | setRandom (double translationMaxMeters, double rotationMaxRadians) |
| Set this to a random transformation with bounded rotation and translation. More...
|
|
void | set (const Eigen::Matrix4d &T_AB) |
| Set from a homogeneous transformation matrix. More...
|
|
void | set (const Eigen::Vector3d &r_AB, const Eigen::Quaternion< double > &q_AB) |
| Set from a translation and quaternion. More...
|
|
void | setIdentity () |
| Set this transformation to identity. More...
|
|
Transformation | inverse () const |
| Returns a copy of the transformation inverted. More...
|
|
Transformation | operator* (const Transformation &rhs) const |
| Multiplication with another transformation object. More...
|
|
Eigen::Vector3d | operator* (const Eigen::Vector3d &rhs) const |
| Transform a direction as v_A = C_AB*v_B (with rhs = hp_B).. More...
|
|
Eigen::Vector4d | operator* (const Eigen::Vector4d &rhs) const |
| Transform a homogenous point as hp_B = T_AB*hp_B (with rhs = hp_B). More...
|
|
Transformation & | operator= (const Transformation &rhs) |
| Assignment – copy. Takes care of proper caching. More...
|
|
template<typename Derived_delta > |
bool | oplus (const Eigen::MatrixBase< Derived_delta > &delta) |
| Apply a small update with delta being 6x1. More...
|
|
template<typename Derived_delta , typename Derived_jacobian > |
bool | oplus (const Eigen::MatrixBase< Derived_delta > &delta, const Eigen::MatrixBase< Derived_jacobian > &jacobian) |
| Apply a small update with delta being 6x1 – the Jacobian is a 7 by 6 matrix. More...
|
|
template<typename Derived_jacobian > |
bool | oplusJacobian (const Eigen::MatrixBase< Derived_jacobian > &jacobian) const |
| Get the Jacobian of the oplus operation (a 7 by 6 matrix). More...
|
|
template<typename Derived_jacobian > |
bool | liftJacobian (const Eigen::MatrixBase< Derived_jacobian > &jacobian) const |
| Gets the jacobian dx/dChi, i.e. lift the minimal Jacobian to a full one (as needed by ceres). More...
|
|
A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of translation r_AB (represented in frame A) and Quaternion q_AB (as an Eigen Quaternion). see also the RSS'13 / IJRR'14 paper or the Thesis. Follows some of the functionality of the SchweizerMesser library by Paul Furgale, but uses Eigen quaternions underneath.
- Warning
- This means the convention is different to SchweizerMesser and the RSS'13 / IJRR'14 paper / the Thesis