NDEVR
API Documentation
SE3Quat

SE(3) rigid body transformation represented by a unit quaternion and translation vector. More...

Collaboration diagram for SE3Quat:
[legend]

Public Member Functions

 SE3Quat ()
 Default constructor.
 SE3Quat (const Matrix3< g_type > &R, const Vector3< g_type > &t)
 Constructs from a rotation matrix and translation vector.
template<typename Derived>
 SE3Quat (const MatrixBase< Derived > &v)
 templaized constructor which allows v to be an arbitrary Eigen Vector type, e.g., Vector6d or Map<Vector6d>
 SE3Quat (const Quaternion< g_type > &q, const Vector3< g_type > &t)
 Constructs from a quaternion and translation vector.
Eigen::Matrix< g_type, 6, 6 > adj () const
 Computes the 6x6 adjoint matrix of this SE3 transform.
void fromMinimalVector (const Vector6d &v)
 Initializes from a minimal 6D vector [t, qx, qy, qz], recovering qw.
void fromVector (const Vector7d &v)
 Initializes from a 7D vector [t, qw, qx, qy, qz].
SE3Quat inverse () const
 Computes the inverse of this SE3 transform.
Vector6d log () const
 Computes the logarithmic map (SE3 -> 6D tangent vector).
Vector3< g_type > map (const Vector3< g_type > &xyz) const
 Transforms a 3D point: R*xyz + t.
void normalizeRotation ()
 Normalizes the rotation quaternion, ensuring positive w.
SE3Quat operator* (const SE3Quat &tr2) const
 Composes two SE3 transforms: result = (*this) * tr2.
Vector3< g_type > operator* (const Vector3< g_type > &v) const
 Transforms a 3D point: t + R*v.
SE3Quatoperator*= (const SE3Quat &tr2)
 In-place composition with another SE3Quat.
g_type operator[] (int i) const
 Const element access: 0-2 = translation, 3-6 = quaternion coeffs.
const Quaternion< g_type > & rotation () const
 Returns a const reference to the rotation quaternion.
void setRotation (const Quaternion< g_type > &r_)
 Sets the rotation quaternion.
void setTranslation (const Vector3< g_type > &t_)
 Sets the translation vector.
Eigen::Matrix< g_type, 4, 4 > to_homogeneous_matrix () const
 Converts to a 4x4 homogeneous transformation matrix.
Vector6d toMinimalVector () const
 Converts to a minimal 6D vector [t, qx, qy, qz].
Vector7d toVector () const
 Converts to a 7D vector [t, qx, qy, qz, qw].
const Vector3< g_type > & translation () const
 Returns a const reference to the translation vector.

Static Public Member Functions

static SE3Quat exp (const Vector6d &update)
 Computes the exponential map from a 6D tangent vector to SE3.

Protected Attributes

Quaternion< g_type > _r
 Rotation component as a unit quaternion.
Vector3< g_type > m_t
 Translation component.

Detailed Description

SE(3) rigid body transformation represented by a unit quaternion and translation vector.

Definition at line 42 of file se3quat.h.

Constructor & Destructor Documentation

◆ SE3Quat() [1/3]

SE3Quat::SE3Quat ( )
inline

Default constructor.

Identity rotation, zero translation.

Definition at line 55 of file se3quat.h.

References _r, and m_t.

Referenced by exp(), inverse(), operator*(), and operator*=().

◆ SE3Quat() [2/3]

SE3Quat::SE3Quat ( const Matrix3< g_type > & R,
const Vector3< g_type > & t )
inline

Constructs from a rotation matrix and translation vector.

Parameters
[in]RThe 3x3 rotation matrix.
[in]tThe translation vector.

Definition at line 63 of file se3quat.h.

References _r, m_t, and normalizeRotation().

◆ SE3Quat() [3/3]

SE3Quat::SE3Quat ( const Quaternion< g_type > & q,
const Vector3< g_type > & t )
inline

Constructs from a quaternion and translation vector.

Parameters
[in]qThe rotation quaternion.
[in]tThe translation vector.

Definition at line 73 of file se3quat.h.

References _r, m_t, and normalizeRotation().

Member Function Documentation

◆ adj()

Eigen::Matrix< g_type, 6, 6 > SE3Quat::adj ( ) const
inline

Computes the 6x6 adjoint matrix of this SE3 transform.

Returns
The adjoint matrix.

Definition at line 309 of file se3quat.h.

References _r, m_t, and skew().

Referenced by EdgeSE3Expmap::linearizeOplus().

◆ exp()

SE3Quat SE3Quat::exp ( const Vector6d & update)
inlinestatic

Computes the exponential map from a 6D tangent vector to SE3.

Parameters
[in]updateThe 6D tangent vector [omega, upsilon].
Returns
The SE3Quat transformation.

Definition at line 272 of file se3quat.h.

References SE3Quat(), cos(), sin(), and skew().

Referenced by VertexSE3Expmap::oplusImpl().

◆ fromMinimalVector()

void SE3Quat::fromMinimalVector ( const Vector6d & v)
inline

Initializes from a minimal 6D vector [t, qx, qy, qz], recovering qw.

Parameters
[in]vThe 6D vector.

Definition at line 195 of file se3quat.h.

References _r, m_t, and sqrt().

◆ fromVector()

void SE3Quat::fromVector ( const Vector7d & v)
inline

Initializes from a 7D vector [t, qw, qx, qy, qz].

Parameters
[in]vThe 7D vector.

Definition at line 176 of file se3quat.h.

References _r, and m_t.

◆ log()

Vector6d SE3Quat::log ( ) const
inline

Computes the logarithmic map (SE3 -> 6D tangent vector).

Returns
A 6D vector [omega, upsilon].

Definition at line 209 of file se3quat.h.

References _r, deltaR(), m_t, PI(), skew(), sqrt(), and tan().

Referenced by EdgeSE3::computeError(), and EdgeSE3Expmap::computeError().

◆ map()

Vector3< g_type > SE3Quat::map ( const Vector3< g_type > & xyz) const
inline

Transforms a 3D point: R*xyz + t.

Parameters
[in]xyzThe point to transform.

Definition at line 263 of file se3quat.h.

References _r, and m_t.

Referenced by EdgeStereoSE3ProjectXYZ::linearizeOplus().

◆ operator*()

Vector3< g_type > SE3Quat::operator* ( const Vector3< g_type > & v) const
inline

Transforms a 3D point: t + R*v.

Parameters
[in]vThe point to transform.

Definition at line 140 of file se3quat.h.

References _r, and m_t.

◆ setRotation()

void SE3Quat::setRotation ( const Quaternion< g_type > & r_)
inline

Sets the rotation quaternion.

Parameters
[in]r_The new rotation quaternion.

Definition at line 119 of file se3quat.h.

References _r.

◆ setTranslation()

void SE3Quat::setTranslation ( const Vector3< g_type > & t_)
inline

Sets the translation vector.

Parameters
[in]t_The new translation.

Definition at line 114 of file se3quat.h.

References m_t.

◆ to_homogeneous_matrix()

Eigen::Matrix< g_type, 4, 4 > SE3Quat::to_homogeneous_matrix ( ) const
inline

Converts to a 4x4 homogeneous transformation matrix.

Returns
The homogeneous matrix.

Definition at line 322 of file se3quat.h.

References _r, and translation().


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