SE(3) rigid body transformation represented by a rotation matrix and translation vector.
More...
|
| | SE3mat () |
| | Default constructor.
|
| | SE3mat (const Eigen::Matrix3< g_type > &R_, const Eigen::Vector3< g_type > &t_) |
| | Constructs from a rotation matrix and translation vector.
|
|
SE3mat | inverse () const |
| | Computes the inverse of this rigid transform.
|
| Eigen::Vector3< g_type > | operator* (const Eigen::Vector3< g_type > &v) const |
| | Transforms a 3D point: R*v + t.
|
|
SE3mat & | operator*= (const SE3mat &T2) |
| | In-place composition with another SE3mat transform.
|
| void | Retract (const Eigen::Vector3< g_type > dr, const Eigen::Vector3< g_type > &dt) |
| | Applies a retraction update: t += R*dt, R *= ExpSO3(dr).
|
|
| static Eigen::Matrix3< g_type > | ExpSO3 (const Eigen::Vector3< g_type > r) |
| | Computes the exponential map from so(3) to SO(3) (Rodrigues formula).
|
| static Eigen::Vector3< g_type > | LogSO3 (const Eigen::Matrix3< g_type > R) |
| | Computes the logarithmic map from SO(3) to so(3).
|
|
|
Eigen::Matrix3< g_type > | R |
| | The 3x3 rotation matrix.
|
|
Eigen::Vector3< g_type > | t |
| | The 3D translation vector.
|
SE(3) rigid body transformation represented by a rotation matrix and translation vector.
Definition at line 8 of file se3mat.h.
◆ SE3mat() [1/2]
◆ SE3mat() [2/2]
| SE3mat::SE3mat |
( |
const Eigen::Matrix3< g_type > & | R_, |
|
|
const Eigen::Vector3< g_type > & | t_ ) |
|
inline |
Constructs from a rotation matrix and translation vector.
- Parameters
-
| [in] | R_ | The 3x3 rotation matrix. |
| [in] | t_ | The 3D translation vector. |
Definition at line 21 of file se3mat.h.
References R, and t.
◆ ExpSO3()
| Eigen::Matrix3< g_type > SE3mat::ExpSO3 |
( |
const Eigen::Vector3< g_type > | r | ) |
|
|
inlinestatic |
Computes the exponential map from so(3) to SO(3) (Rodrigues formula).
- Parameters
-
| [in] | r | The rotation vector (axis * angle). |
- Returns
- The 3x3 rotation matrix.
Definition at line 64 of file se3mat.h.
References cos(), and sin().
Referenced by Retract().
◆ LogSO3()
| Eigen::Vector3< g_type > SE3mat::LogSO3 |
( |
const Eigen::Matrix3< g_type > | R | ) |
|
|
inlinestatic |
Computes the logarithmic map from SO(3) to so(3).
- Parameters
-
| [in] | R | The 3x3 rotation matrix. |
- Returns
- The rotation vector (axis * angle).
Definition at line 82 of file se3mat.h.
References R, and sin().
◆ operator*()
| Eigen::Vector3< g_type > SE3mat::operator* |
( |
const Eigen::Vector3< g_type > & | v | ) |
const |
|
inline |
Transforms a 3D point: R*v + t.
- Parameters
-
| [in] | v | The point to transform. |
Definition at line 39 of file se3mat.h.
References R, and t.
◆ Retract()
| void SE3mat::Retract |
( |
const Eigen::Vector3< g_type > | dr, |
|
|
const Eigen::Vector3< g_type > & | dt ) |
|
inline |
Applies a retraction update: t += R*dt, R *= ExpSO3(dr).
- Parameters
-
| [in] | dr | The rotation update vector. |
| [in] | dt | The translation update vector. |
Definition at line 30 of file se3mat.h.
References ExpSO3(), R, and t.
The documentation for this class was generated from the following file: