manif-geom-cpp
|
Class representing a member of the \(SE(3)\) manifold, or a 3D rigid body transform. More...
#include <SE3.h>
Public Member Functions | |
SE3 () | |
Create a transform (with garbage data). | |
SE3 (const Ref< const Vec7T > &arr) | |
Create a transform from an array representing all transform fields in \(\begin{bmatrix}\boldsymbol{t} &
\boldsymbol{q}\end{bmatrix}^\top\). | |
SE3 (const SE3 &x) | |
Copy constructor from another transform. | |
SE3 (const T *data) | |
Create a transform from a pointer array representing all transform fields in \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\). | |
T & | operator[] (int i) |
Access a field from \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\). | |
const Map< Vec3T > & | t () const |
Access the translation vector \(\boldsymbol{t}\in\mathbb{R}^3\). | |
const SO3< T > & | q () const |
Access the rotation \(\boldsymbol{q}\in SO(3)\). | |
Map< Vec3T > & | t () |
Access the translation vector \(\boldsymbol{t}\in\mathbb{R}^3\). | |
SO3< T > & | q () |
Access the rotation \(\boldsymbol{q}\in SO(3)\). | |
const Vec7T | elements () const |
Access all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\). | |
Vec7T | array () const |
Access all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\). | |
T * | data () |
Access pointer to all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\). | |
const T * | data () const |
Access pointer to all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\). | |
SE3 | copy () const |
Get a deep copy of the current transform. | |
Mat4T | H () const |
Convert the transform to matrix representation \(\begin{bmatrix}\boldsymbol{R} & \boldsymbol{t}
\\ \boldsymbol{0} & 1\end{bmatrix}\in\mathbb{R}^{4\times 4}\). | |
SE3 | inverse () const |
Obtain the inverse transform \(\boldsymbol{T}_A^B\rightarrow \boldsymbol{T}_B^A\). | |
SE3 & | invert () |
Invert the current transform \(\boldsymbol{T}_A^B\rightarrow \boldsymbol{T}_B^A\). | |
template<typename Tout = T, typename T2 > | |
SE3< Tout > | otimes (const SE3< T2 > &x) const |
Implementation of group composition: \(\boldsymbol{T}_B^C \otimes \boldsymbol{T}_A^B\rightarrow
\boldsymbol{T}_A^C\). | |
template<typename Tout = T, typename T2 > | |
SE3< Tout > | oplus (const Matrix< T2, 6, 1 > &delta) const |
Implementation of tangent space group perturbations: \(\boldsymbol{T}_A^B\oplus \boldsymbol{t}_B^{B'}
\rightarrow \boldsymbol{T}_A^{B'}\). | |
template<typename Tout = T, typename T2 > | |
Matrix< Tout, 6, 1 > | ominus (const SE3< T2 > &x) const |
Implementation of group subtraction: \(\boldsymbol{T}_A^B\ominus \boldsymbol{T}_A^{B'} \rightarrow
\boldsymbol{t}_B^{B'}\). | |
SE3 & | operator= (const SE3 &x) |
Copy constructor. | |
template<typename T2 > | |
SE3 | operator* (const SE3< T2 > &x) const |
Invocation of otimes via multiplication. | |
template<typename T2 > | |
SE3 & | operator*= (const SE3< T2 > &x) |
Invocation of otimes via multiplication. | |
SE3 & | operator*= (const double &s) |
Scale a transform by a scalar. | |
SE3 & | operator/= (const double &s) |
Scale a transform by a scalar. | |
SE3 | operator/ (const double &s) const |
Scale a transform by a scalar. | |
template<typename Tout = T, typename T2 > | |
Matrix< Tout, 3, 1 > | operator* (const Matrix< T2, 3, 1 > &v) const |
Transform a vector via multiplication: \(\boldsymbol{T}_A^B\boldsymbol{t}^A \rightarrow
\boldsymbol{t}^B\). | |
Vec3T | operator* (const Vec3T &v) const |
Transform a vector via multiplication: \(\boldsymbol{T}_A^B\boldsymbol{t}^A \rightarrow
\boldsymbol{t}^B\). | |
SE3 | operator+ (const Vec6T &v) const |
Invocation of oplus via addition. | |
SE3 & | operator+= (const Vec6T &v) |
Invocation of oplus via addition. | |
template<typename T2 > | |
Vec6T | operator- (const SE3< T2 > &x) const |
Invocation of ominus via subtraction. | |
template<typename T2 > | |
SE3< T2 > | cast () const |
Cast the underlying numeric type. | |
Static Public Member Functions | |
static SE3 | random () |
Obtain a random rigid body transform. | |
static SE3 | identity () |
Obtain an identity \(SE(3)\) transform. | |
static SE3 | nans () |
Obtain a transform full of NaNs. | |
static SE3 | fromH (const Mat4T &m) |
Convert a transform matrix \(\begin{bmatrix}\boldsymbol{R} & \boldsymbol{t} \\ \boldsymbol{0} &
1\end{bmatrix}\) into a \(SE(3)\) transform. | |
static SE3 | fromVecAndQuat (const T tx, const T ty, const T tz, const T qw, const T qx, const T qy, const T qz) |
Construct a transform from the individual fields. | |
static SE3 | fromVecAndQuat (const Vec3T &tvec, const Vec4T &qvec) |
Construct a transform from a translation vector and rotation fields vector. | |
static SE3 | fromVecAndQuat (const Vec3T &t, const SO3< T > &q) |
Construct a transform from a translation vector and a rotation object. | |
static SE3 | fromVecAndQuat (const Vec3T &tvec, const Quaternion< T > quat) |
Construct a transform from a translation vector and an Eigen Quaternion object. | |
static Mat4T | hat (const Vec6T &omega) |
Hat operator implementation, which coverts the tangent-space vector representation to the corresponding Lie algebra: \(\mathbb{R}^6\rightarrow \mathfrak{se}(3)\). | |
static Vec6T | vee (const Mat4T &Omega) |
Vee operator implementation, which coverts the Lie algebra representation to a tangent-space vector representation: \(\mathfrak{se}(3) \rightarrow \mathbb{R}^6\). | |
static Mat4T | log (const SE3 &x) |
Logarithmic chart map implementation: \(SE(3) \rightarrow \mathfrak{se}(3)\). | |
static Vec6T | Log (const SE3 &x) |
Logarithmic chart map implementation: \(SE(3) \rightarrow \mathbb{R}^6\). | |
static SE3 | exp (const Mat4T &Omega) |
Exponential chart map implementation: \(\mathfrak{se}(3) \rightarrow SE(3)\). | |
static SE3 | Exp (const Vec6T &omega) |
Exponential chart map implementation: \(\mathbb{R}^6 \rightarrow SE(3)\). | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Map< Vec7T > | arr_ |
Memory-mapped array representing all transform fields in \(\begin{bmatrix}\boldsymbol{t} &
\boldsymbol{q}\end{bmatrix}^\top\). | |
Map< Vec3T > | t_ |
Memory-mapped array representing only the translation component of the transform \(\boldsymbol{t}\). | |
SO3< T > | q_ |
Memory-mapped array representing only the rotation component of the transform \(\boldsymbol{q}\). | |
Class representing a member of the \(SE(3)\) manifold, or a 3D rigid body transform.
Create a transform from an array representing all transform fields in \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Copy constructor from another transform.
Create a transform from a pointer array representing all transform fields in \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Access all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Cast the underlying numeric type.
Access pointer to all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Access pointer to all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Access all elements of \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Exponential chart map implementation: \(\mathfrak{se}(3) \rightarrow SE(3)\).
Exponential chart map implementation: \(\mathbb{R}^6 \rightarrow SE(3)\).
Convert a transform matrix \(\begin{bmatrix}\boldsymbol{R} & \boldsymbol{t} \\ \boldsymbol{0} & 1\end{bmatrix}\) into a \(SE(3)\) transform.
|
inlinestatic |
Construct a transform from the individual fields.
tx | First component of the translation \(\boldsymbol{t}\in\mathbb{R}^3\). |
ty | Second component of the translation \(\boldsymbol{t}\in\mathbb{R}^3\). |
tz | Third component of the translation \(\boldsymbol{t}\in\mathbb{R}^3\). |
qw | Real component of the rotation \(\boldsymbol{q}\in SO(3)\). |
qx | First imaginary component of the rotation \(\boldsymbol{q}\in SO(3)\). |
qy | Second imaginary component of the rotation \(\boldsymbol{q}\in SO(3)\). |
qz | Third imaginary component of the rotation \(\boldsymbol{q}\in SO(3)\). |
Construct a transform from a translation vector and a rotation object.
t | The translation vector \(\boldsymbol{t}\in\mathbb{R}^3\). |
q | The rotation \(\boldsymbol{q}\in SO(3)\). |
Construct a transform from a translation vector and an Eigen Quaternion object.
t | The translation vector \(\boldsymbol{t}\in\mathbb{R}^3\). |
q | The Eigen Quaternion \(\boldsymbol{q}\in SO(3)\). |
Construct a transform from a translation vector and rotation fields vector.
tvec | The translation vector \(\boldsymbol{t}\in\mathbb{R}^3\). |
qvec | The rotation represented as an array \(\boldsymbol{q}\in\mathbb{R}^4\). |
Convert the transform to matrix representation \(\begin{bmatrix}\boldsymbol{R} & \boldsymbol{t} \\ \boldsymbol{0} & 1\end{bmatrix}\in\mathbb{R}^{4\times 4}\).
Hat operator implementation, which coverts the tangent-space vector representation to the corresponding Lie algebra: \(\mathbb{R}^6\rightarrow \mathfrak{se}(3)\).
Obtain an identity \(SE(3)\) transform.
Obtain the inverse transform \(\boldsymbol{T}_A^B\rightarrow \boldsymbol{T}_B^A\).
Invert the current transform \(\boldsymbol{T}_A^B\rightarrow \boldsymbol{T}_B^A\).
Logarithmic chart map implementation: \(SE(3) \rightarrow \mathfrak{se}(3)\).
Logarithmic chart map implementation: \(SE(3) \rightarrow \mathbb{R}^6\).
Implementation of group subtraction: \(\boldsymbol{T}_A^B\ominus \boldsymbol{T}_A^{B'} \rightarrow \boldsymbol{t}_B^{B'}\).
Transform a vector via multiplication: \(\boldsymbol{T}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).
Invocation of otimes via multiplication.
Transform a vector via multiplication: \(\boldsymbol{T}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).
Scale a transform by a scalar.
Under the hood, this converts the transform into a tangent-space vector, scales the vector, then converts the scaled vector back to a transform.
Invocation of oplus via addition.
Invocation of oplus via addition.
Scale a transform by a scalar.
Under the hood, this converts the transform into a tangent-space vector, scales the vector, then converts the scaled vector back to a transform.
Scale a transform by a scalar.
Under the hood, this converts the transform into a tangent-space vector, scales the vector, then converts the scaled vector back to a transform.
Access a field from \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Implementation of tangent space group perturbations: \(\boldsymbol{T}_A^B\oplus \boldsymbol{t}_B^{B'} \rightarrow \boldsymbol{T}_A^{B'}\).
|
inline |
Implementation of group composition: \(\boldsymbol{T}_B^C \otimes \boldsymbol{T}_A^B\rightarrow \boldsymbol{T}_A^C\).
Access the rotation \(\boldsymbol{q}\in SO(3)\).
Access the rotation \(\boldsymbol{q}\in SO(3)\).
Obtain a random rigid body transform.
The rotation component \(\mathbf{q}_B^W\) will be normalized, but the translation component \(\mathbf{t}_{B/W}^W\) will not (each component will be between 0 and 1).
Access the translation vector \(\boldsymbol{t}\in\mathbb{R}^3\).
Access the translation vector \(\boldsymbol{t}\in\mathbb{R}^3\).
Vee operator implementation, which coverts the Lie algebra representation to a tangent-space vector representation: \(\mathfrak{se}(3) \rightarrow \mathbb{R}^6\).
Memory-mapped array representing all transform fields in \(\begin{bmatrix}\boldsymbol{t} & \boldsymbol{q}\end{bmatrix}^\top\).
Memory-mapped array representing only the rotation component of the transform \(\boldsymbol{q}\).
Memory-mapped array representing only the translation component of the transform \(\boldsymbol{t}\).