manif-geom-cpp
|
Class representing a member of the \(SO(3)\) manifold, or a 3D rotation. More...
#include <SO3.h>
Public Member Functions | |
SO3 () | |
Create a rotation (with garbage data). | |
SO3 (const Ref< const Vec4T > &arr) | |
Create a transform from an array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^4\). | |
SO3 (const SO3 &q) | |
Copy constructor from another rotation. | |
SO3 (const T *data) | |
Create a rotation from a pointer array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^4\). | |
T & | operator[] (int i) |
Access a field from \(\boldsymbol{q}\in\mathbb{R}^4\). | |
const T & | w () const |
Access the real element of the rotation. | |
const T & | x () const |
Access the first imaginary element of the rotation. | |
const T & | y () const |
Access the second imaginary element of the rotation. | |
const T & | z () const |
Access the third imaginary element of the rotation. | |
T & | w () |
Access the real element of the rotation. | |
T & | x () |
Access the first imaginary element of the rotation. | |
T & | y () |
Access the second imaginary element of the rotation. | |
T & | z () |
Access the third imaginary element of the rotation. | |
const Vec4T | elements () const |
Access all elements of \(\boldsymbol{q}\in\mathbb{R}^4\). | |
Vec4T | array () const |
Access all elements of \(\boldsymbol{q}\in\mathbb{R}^4\). | |
T * | data () |
Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\). | |
const T * | data () const |
Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\). | |
SO3 | copy () const |
Get a deep copy of the current rotation. | |
void | normalize () |
Normalize the elements of \(\boldsymbol{q}\) to make it a valid rotation. | |
SO3 | normalized () |
Obtain a normalized copy of the current rotation. | |
Mat3T | R () const |
Convert the rotation to matrix representation \(\boldsymbol{R}\in \mathbb{R}^{3\times 3}\). | |
SO3 | inverse () const |
Obtain the inverse rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\). | |
SO3 & | invert () |
Invert the current rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\). | |
T | roll () const |
Obtain the roll component of the yaw-pitch-roll successive-axes Euler angle representation. | |
T | pitch () const |
Obtain the pitch component of the yaw-pitch-roll successive-axes Euler angle representation. | |
T | yaw () const |
Obtain the yaw component of the yaw-pitch-roll successive-axes Euler angle representation. | |
Vec3T | toEuler () const |
Obtain the Euler angle representation as a 3-vector. | |
Mat4T | qMatLeft () const |
Obtain an equivalent 4-by-4 matrix representation of \(\boldsymbol{q}\rightarrow [\boldsymbol{q}]_L\) such that \(\boldsymbol{q}\otimes \boldsymbol{q}_{\text{other}}=[\boldsymbol{q}]_L
\boldsymbol{q}_{\text{other}}\). | |
template<typename Tout = T, typename T2 > | |
SO3< Tout > | otimes (const SO3< T2 > &q) const |
Implementation of group composition: \(\boldsymbol{q}_B^C \otimes \boldsymbol{q}_A^B\rightarrow
\boldsymbol{q}_A^C\). | |
template<typename Tout = T, typename T2 > | |
SO3< Tout > | oplus (const Matrix< T2, 3, 1 > &delta) const |
Implementation of tangent space group perturbations: \(\boldsymbol{q}_A^B\oplus
\boldsymbol{\theta}_B^{B'} \rightarrow \boldsymbol{q}_A^{B'}\). | |
template<typename Tout = T, typename T2 > | |
Matrix< Tout, 3, 1 > | ominus (const SO3< T2 > &q) const |
Implementation of group subtraction: \(\boldsymbol{q}_A^B\ominus \boldsymbol{q}_A^{B'} \rightarrow
\boldsymbol{\theta}_B^{B'}\). | |
SO3 & | operator= (const SO3 &q) |
Copy constructor. | |
template<typename T2 > | |
SO3 | operator* (const SO3< T2 > &q) const |
Invocation of otimes via multiplication. | |
template<typename T2 > | |
SO3 & | operator*= (const SO3< T2 > &q) |
Invocation of otimes via multiplication. | |
SO3 & | operator*= (const double &s) |
Scale a rotation by a scalar. | |
SO3 & | operator/= (const double &s) |
Scale a rotation by a scalar. | |
SO3 | operator/ (const double &s) const |
Scale a rotation 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{q}_A^B\boldsymbol{t}^A \rightarrow
\boldsymbol{t}^B\). | |
Vec3T | operator* (const Vec3T &v) const |
Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow
\boldsymbol{t}^B\). | |
SO3 | operator+ (const Vec3T &v) const |
Invocation of oplus via addition. | |
SO3 & | operator+= (const Vec3T &v) |
Invocation of oplus via addition. | |
template<typename T2 > | |
Vec3T | operator- (const SO3< T2 > &q) const |
Invocation of ominus via subtraction. | |
template<typename T2 > | |
SO3< T2 > | cast () const |
Cast the underlying numeric type. | |
Static Public Member Functions | |
static SO3 | random () |
Obtain a random rotation. | |
static SO3 | identity () |
Obtain an identity \(SO(3)\) rotation. | |
static SO3 | nans () |
Obtain a rotation full of NaNs. | |
static SO3 | fromAxisAngle (const Vec3T &axis, const T angle) |
Convert an angle (in radians) with accompanying axis (defined by a vector) into a rotation. | |
static SO3 | fromEuler (const T roll, const T pitch, const T yaw) |
Construct a rotation from yaw-pitch-roll successive-axes Euler angles. | |
static SO3 | fromR (const Mat3T &m) |
Convert a rotation matrix \(\boldsymbol{R}\in\mathbb{R}^{3\times 3}\) to a \(SO(3)\) rotation. | |
static SO3 | fromTwoUnitVectors (const Vec3T &u, const Vec3T &v) |
Given two unit vectors \(\boldsymbol{u},\boldsymbol{v}\in \mathbb{R}^3\), returns the rotation that rotates \(\boldsymbol{u}\rightarrow\boldsymbol{v}\). | |
static SO3 | fromQuat (const T qw, const T qx, const T qy, const T qz) |
Construct a rotation from the individual fields. | |
static SO3 | fromQuat (const Vec4T &qvec) |
Construct a rotation from a rotation fields vector. | |
static SO3 | fromQuat (const Quaternion< T > quat) |
Construct a rotation from an Eigen quaternion. | |
static Mat3T | hat (const Vec3T &omega) |
Hat operator implementation, which coverts the tangent-space vector representation to the corresponding Lie algebra: \(\mathbb{R}^3\rightarrow \mathfrak{so}(3)\). | |
static Vec3T | vee (const Mat3T &Omega) |
Vee operator implementation, which coverts the Lie algebra representation to a tangent-space vector representation: \(\mathfrak{so}(3) \rightarrow \mathbb{R}^3\). | |
static Mat3T | log (const SO3 &q) |
Logarithmic chart map implementation: \(SO(3) \rightarrow \mathfrak{so}(3)\). | |
static Vec3T | Log (const SO3 &q) |
Logarithmic chart map implementation: \(SO(3) \rightarrow \mathbb{R}^3\). | |
static SO3 | exp (const Mat3T &Omega) |
Exponential chart map implementation: \(\mathfrak{so}(3) \rightarrow SO(3)\). | |
static SO3 | Exp (const Vec3T &omega) |
Exponential chart map implementation: \(\mathbb{R}^3 \rightarrow SO(3)\). | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Map< Vec4T > | arr_ |
Memory-mapped array representing all rotation fields in \(\boldsymbol{q}\). | |
Class representing a member of the \(SO(3)\) manifold, or a 3D rotation.
Create a transform from an array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^4\).
Copy constructor from another rotation.
Create a rotation from a pointer array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^4\).
Access all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).
Cast the underlying numeric type.
Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).
Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).
Access all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).
Exponential chart map implementation: \(\mathfrak{so}(3) \rightarrow SO(3)\).
Exponential chart map implementation: \(\mathbb{R}^3 \rightarrow SO(3)\).
Convert an angle (in radians) with accompanying axis (defined by a vector) into a rotation.
Construct a rotation from yaw-pitch-roll successive-axes Euler angles.
Construct a rotation from an Eigen quaternion.
quat | The Eigen quaternion. |
Construct a rotation from the individual fields.
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 rotation from a rotation fields vector.
qvec | The rotation represented as an array \(\boldsymbol{q}\in\mathbb{R}^4\). |
Convert a rotation matrix \(\boldsymbol{R}\in\mathbb{R}^{3\times 3}\) to a \(SO(3)\) rotation.
Given two unit vectors \(\boldsymbol{u},\boldsymbol{v}\in \mathbb{R}^3\), returns the rotation that rotates \(\boldsymbol{u}\rightarrow\boldsymbol{v}\).
Naturally, there is roll ambiguity in such a transform, so watch out.
Hat operator implementation, which coverts the tangent-space vector representation to the corresponding Lie algebra: \(\mathbb{R}^3\rightarrow \mathfrak{so}(3)\).
Obtain an identity \(SO(3)\) rotation.
Obtain the inverse rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\).
Invert the current rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\).
Logarithmic chart map implementation: \(SO(3) \rightarrow \mathfrak{so}(3)\).
Logarithmic chart map implementation: \(SO(3) \rightarrow \mathbb{R}^3\).
Normalize the elements of \(\boldsymbol{q}\) to make it a valid rotation.
Obtain a normalized copy of the current rotation.
Implementation of group subtraction: \(\boldsymbol{q}_A^B\ominus \boldsymbol{q}_A^{B'} \rightarrow \boldsymbol{\theta}_B^{B'}\).
Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).
Invocation of otimes via multiplication.
Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).
Scale a rotation by a scalar.
Under the hood, this converts the rotation into a tangent-space vector, scales the vector, then converts the scaled vector back to a rotation.
Invocation of oplus via addition.
Invocation of oplus via addition.
Scale a rotation by a scalar.
Under the hood, this converts the rotation into a tangent-space vector, scales the vector, then converts the scaled vector back to a rotation.
Scale a rotation by a scalar.
Under the hood, this converts the rotation into a tangent-space vector, scales the vector, then converts the scaled vector back to a rotation.
Access a field from \(\boldsymbol{q}\in\mathbb{R}^4\).
Implementation of tangent space group perturbations: \(\boldsymbol{q}_A^B\oplus \boldsymbol{\theta}_B^{B'} \rightarrow \boldsymbol{q}_A^{B'}\).
|
inline |
Implementation of group composition: \(\boldsymbol{q}_B^C \otimes \boldsymbol{q}_A^B\rightarrow \boldsymbol{q}_A^C\).
Obtain the pitch component of the yaw-pitch-roll successive-axes Euler angle representation.
Obtain an equivalent 4-by-4 matrix representation of \(\boldsymbol{q}\rightarrow [\boldsymbol{q}]_L\) such that \(\boldsymbol{q}\otimes \boldsymbol{q}_{\text{other}}=[\boldsymbol{q}]_L \boldsymbol{q}_{\text{other}}\).
Convert the rotation to matrix representation \(\boldsymbol{R}\in \mathbb{R}^{3\times 3}\).
Obtain a random rotation.
The rotation \(\mathbf{q}_B^W\) will be normalized.
Obtain the roll component of the yaw-pitch-roll successive-axes Euler angle representation.
Obtain the Euler angle representation as a 3-vector.
Vee operator implementation, which coverts the Lie algebra representation to a tangent-space vector representation: \(\mathfrak{so}(3) \rightarrow \mathbb{R}^3\).
Access the real element of the rotation.
Access the first imaginary element of the rotation.
Access the first imaginary element of the rotation.
Access the second imaginary element of the rotation.
Access the second imaginary element of the rotation.
Obtain the yaw component of the yaw-pitch-roll successive-axes Euler angle representation.
Access the third imaginary element of the rotation.
Access the third imaginary element of the rotation.
Memory-mapped array representing all rotation fields in \(\boldsymbol{q}\).