manif-geom-cpp
Loading...
Searching...
No Matches
SO3< T > Class Template Reference

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\).
 
Toperator[] (int i)
 Access a field from \(\boldsymbol{q}\in\mathbb{R}^4\).
 
const Tw () const
 Access the real element of the rotation.
 
const Tx () const
 Access the first imaginary element of the rotation.
 
const Ty () const
 Access the second imaginary element of the rotation.
 
const Tz () const
 Access the third imaginary element of the rotation.
 
Tw ()
 Access the real element of the rotation.
 
Tx ()
 Access the first imaginary element of the rotation.
 
Ty ()
 Access the second imaginary element of the rotation.
 
Tz ()
 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\).
 
Tdata ()
 Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).
 
const Tdata () 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\).
 
SO3invert ()
 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< Toutoplus (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'}\).
 
SO3operator= (const SO3 &q)
 Copy constructor.
 
template<typename T2 >
SO3 operator* (const SO3< T2 > &q) const
 Invocation of otimes via multiplication.
 
template<typename T2 >
SO3operator*= (const SO3< T2 > &q)
 Invocation of otimes via multiplication.
 
SO3operator*= (const double &s)
 Scale a rotation by a scalar.
 
SO3operator/= (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.
 
SO3operator+= (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< T2cast () 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}\).
 

Detailed Description

template<typename T>
class SO3< T >

Class representing a member of the \(SO(3)\) manifold, or a 3D rotation.

Constructor & Destructor Documentation

◆ SO3() [1/4]

template<typename T >
SO3< T >::SO3 ( )
inline

Create a rotation (with garbage data).

◆ SO3() [2/4]

template<typename T >
SO3< T >::SO3 ( const Ref< const Vec4T > & arr)
inline

Create a transform from an array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ SO3() [3/4]

template<typename T >
SO3< T >::SO3 ( const SO3< T > & q)
inline

Copy constructor from another rotation.

◆ SO3() [4/4]

template<typename T >
SO3< T >::SO3 ( const T * data)
inline

Create a rotation from a pointer array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^4\).

Member Function Documentation

◆ array()

template<typename T >
Vec4T SO3< T >::array ( ) const
inline

Access all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ cast()

template<typename T >
template<typename T2 >
SO3< T2 > SO3< T >::cast ( ) const
inline

Cast the underlying numeric type.

◆ copy()

template<typename T >
SO3 SO3< T >::copy ( ) const
inline

Get a deep copy of the current rotation.

◆ data() [1/2]

template<typename T >
T * SO3< T >::data ( )
inline

Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ data() [2/2]

template<typename T >
const T * SO3< T >::data ( ) const
inline

Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ elements()

template<typename T >
const Vec4T SO3< T >::elements ( ) const
inline

Access all elements of \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ exp()

template<typename T >
static SO3 SO3< T >::exp ( const Mat3T & Omega)
inlinestatic

Exponential chart map implementation: \(\mathfrak{so}(3) \rightarrow SO(3)\).

◆ Exp()

template<typename T >
static SO3 SO3< T >::Exp ( const Vec3T & omega)
inlinestatic

Exponential chart map implementation: \(\mathbb{R}^3 \rightarrow SO(3)\).

◆ fromAxisAngle()

template<typename T >
static SO3 SO3< T >::fromAxisAngle ( const Vec3T & axis,
const T angle )
inlinestatic

Convert an angle (in radians) with accompanying axis (defined by a vector) into a rotation.

◆ fromEuler()

template<typename T >
static SO3 SO3< T >::fromEuler ( const T roll,
const T pitch,
const T yaw )
inlinestatic

Construct a rotation from yaw-pitch-roll successive-axes Euler angles.

◆ fromQuat() [1/3]

template<typename T >
static SO3 SO3< T >::fromQuat ( const Quaternion< T > quat)
inlinestatic

Construct a rotation from an Eigen quaternion.

Parameters
quatThe Eigen quaternion.

◆ fromQuat() [2/3]

template<typename T >
static SO3 SO3< T >::fromQuat ( const T qw,
const T qx,
const T qy,
const T qz )
inlinestatic

Construct a rotation from the individual fields.

Parameters
qwReal component of the rotation \(\boldsymbol{q}\in SO(3)\).
qxFirst imaginary component of the rotation \(\boldsymbol{q}\in SO(3)\).
qySecond imaginary component of the rotation \(\boldsymbol{q}\in SO(3)\).
qzThird imaginary component of the rotation \(\boldsymbol{q}\in SO(3)\).

◆ fromQuat() [3/3]

template<typename T >
static SO3 SO3< T >::fromQuat ( const Vec4T & qvec)
inlinestatic

Construct a rotation from a rotation fields vector.

Parameters
qvecThe rotation represented as an array \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ fromR()

template<typename T >
static SO3 SO3< T >::fromR ( const Mat3T & m)
inlinestatic

Convert a rotation matrix \(\boldsymbol{R}\in\mathbb{R}^{3\times 3}\) to a \(SO(3)\) rotation.

◆ fromTwoUnitVectors()

template<typename T >
static SO3 SO3< T >::fromTwoUnitVectors ( const Vec3T & u,
const Vec3T & v )
inlinestatic

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()

template<typename T >
static Mat3T SO3< T >::hat ( const Vec3T & omega)
inlinestatic

Hat operator implementation, which coverts the tangent-space vector representation to the corresponding Lie algebra: \(\mathbb{R}^3\rightarrow \mathfrak{so}(3)\).

◆ identity()

template<typename T >
static SO3 SO3< T >::identity ( )
inlinestatic

Obtain an identity \(SO(3)\) rotation.

◆ inverse()

template<typename T >
SO3 SO3< T >::inverse ( ) const
inline

Obtain the inverse rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\).

◆ invert()

template<typename T >
SO3 & SO3< T >::invert ( )
inline

Invert the current rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\).

◆ log()

template<typename T >
static Mat3T SO3< T >::log ( const SO3< T > & q)
inlinestatic

Logarithmic chart map implementation: \(SO(3) \rightarrow \mathfrak{so}(3)\).

◆ Log()

template<typename T >
static Vec3T SO3< T >::Log ( const SO3< T > & q)
inlinestatic

Logarithmic chart map implementation: \(SO(3) \rightarrow \mathbb{R}^3\).

◆ nans()

template<typename T >
static SO3 SO3< T >::nans ( )
inlinestatic

Obtain a rotation full of NaNs.

◆ normalize()

template<typename T >
void SO3< T >::normalize ( )
inline

Normalize the elements of \(\boldsymbol{q}\) to make it a valid rotation.

◆ normalized()

template<typename T >
SO3 SO3< T >::normalized ( )
inline

Obtain a normalized copy of the current rotation.

◆ ominus()

template<typename T >
template<typename Tout = T, typename T2 >
Matrix< Tout, 3, 1 > SO3< T >::ominus ( const SO3< T2 > & q) const
inline

Implementation of group subtraction: \(\boldsymbol{q}_A^B\ominus \boldsymbol{q}_A^{B'} \rightarrow \boldsymbol{\theta}_B^{B'}\).

◆ operator*() [1/3]

template<typename T >
template<typename Tout = T, typename T2 >
Matrix< Tout, 3, 1 > SO3< T >::operator* ( const Matrix< T2, 3, 1 > & v) const
inline

Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).

◆ operator*() [2/3]

template<typename T >
template<typename T2 >
SO3 SO3< T >::operator* ( const SO3< T2 > & q) const
inline

Invocation of otimes via multiplication.

◆ operator*() [3/3]

template<typename T >
Vec3T SO3< T >::operator* ( const Vec3T & v) const
inline

Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).

◆ operator*=() [1/2]

template<typename T >
SO3 & SO3< T >::operator*= ( const double & s)
inline

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.

◆ operator*=() [2/2]

template<typename T >
template<typename T2 >
SO3 & SO3< T >::operator*= ( const SO3< T2 > & q)
inline

Invocation of otimes via multiplication.

◆ operator+()

template<typename T >
SO3 SO3< T >::operator+ ( const Vec3T & v) const
inline

Invocation of oplus via addition.

◆ operator+=()

template<typename T >
SO3 & SO3< T >::operator+= ( const Vec3T & v)
inline

Invocation of oplus via addition.

◆ operator-()

template<typename T >
template<typename T2 >
Vec3T SO3< T >::operator- ( const SO3< T2 > & q) const
inline

Invocation of ominus via subtraction.

◆ operator/()

template<typename T >
SO3 SO3< T >::operator/ ( const double & s) const
inline

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.

◆ operator/=()

template<typename T >
SO3 & SO3< T >::operator/= ( const double & s)
inline

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.

◆ operator=()

template<typename T >
SO3 & SO3< T >::operator= ( const SO3< T > & q)
inline

Copy constructor.

◆ operator[]()

template<typename T >
T & SO3< T >::operator[] ( int i)
inline

Access a field from \(\boldsymbol{q}\in\mathbb{R}^4\).

◆ oplus()

template<typename T >
template<typename Tout = T, typename T2 >
SO3< Tout > SO3< T >::oplus ( const Matrix< T2, 3, 1 > & delta) const
inline

Implementation of tangent space group perturbations: \(\boldsymbol{q}_A^B\oplus \boldsymbol{\theta}_B^{B'} \rightarrow \boldsymbol{q}_A^{B'}\).

◆ otimes()

template<typename T >
template<typename Tout = T, typename T2 >
SO3< Tout > SO3< T >::otimes ( const SO3< T2 > & q) const
inline

Implementation of group composition: \(\boldsymbol{q}_B^C \otimes \boldsymbol{q}_A^B\rightarrow \boldsymbol{q}_A^C\).

◆ pitch()

template<typename T >
T SO3< T >::pitch ( ) const
inline

Obtain the pitch component of the yaw-pitch-roll successive-axes Euler angle representation.

◆ qMatLeft()

template<typename T >
Mat4T SO3< T >::qMatLeft ( ) const
inline

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}}\).

◆ R()

template<typename T >
Mat3T SO3< T >::R ( ) const
inline

Convert the rotation to matrix representation \(\boldsymbol{R}\in \mathbb{R}^{3\times 3}\).

◆ random()

template<typename T >
static SO3 SO3< T >::random ( )
inlinestatic

Obtain a random rotation.

Returns
A random rotation \(\boldsymbol{q}_B^W\in SO(3)\).

The rotation \(\mathbf{q}_B^W\) will be normalized.

◆ roll()

template<typename T >
T SO3< T >::roll ( ) const
inline

Obtain the roll component of the yaw-pitch-roll successive-axes Euler angle representation.

◆ toEuler()

template<typename T >
Vec3T SO3< T >::toEuler ( ) const
inline

Obtain the Euler angle representation as a 3-vector.

◆ vee()

template<typename T >
static Vec3T SO3< T >::vee ( const Mat3T & Omega)
inlinestatic

Vee operator implementation, which coverts the Lie algebra representation to a tangent-space vector representation: \(\mathfrak{so}(3) \rightarrow \mathbb{R}^3\).

◆ w() [1/2]

template<typename T >
T & SO3< T >::w ( )
inline

Access the real element of the rotation.

◆ w() [2/2]

template<typename T >
const T & SO3< T >::w ( ) const
inline

Access the real element of the rotation.

◆ x() [1/2]

template<typename T >
T & SO3< T >::x ( )
inline

Access the first imaginary element of the rotation.

◆ x() [2/2]

template<typename T >
const T & SO3< T >::x ( ) const
inline

Access the first imaginary element of the rotation.

◆ y() [1/2]

template<typename T >
T & SO3< T >::y ( )
inline

Access the second imaginary element of the rotation.

◆ y() [2/2]

template<typename T >
const T & SO3< T >::y ( ) const
inline

Access the second imaginary element of the rotation.

◆ yaw()

template<typename T >
T SO3< T >::yaw ( ) const
inline

Obtain the yaw component of the yaw-pitch-roll successive-axes Euler angle representation.

◆ z() [1/2]

template<typename T >
T & SO3< T >::z ( )
inline

Access the third imaginary element of the rotation.

◆ z() [2/2]

template<typename T >
const T & SO3< T >::z ( ) const
inline

Access the third imaginary element of the rotation.

Member Data Documentation

◆ arr_

template<typename T >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Map<Vec4T> SO3< T >::arr_

Memory-mapped array representing all rotation fields in \(\boldsymbol{q}\).


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