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

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

#include <SO2.h>

Public Member Functions

 SO2 ()
 Create a rotation (with garbage data).
 
 SO2 (const Ref< const Vec2T > &arr)
 Create a transform from an array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^2\).
 
 SO2 (const SO2 &q)
 Copy constructor from another rotation.
 
 SO2 (const T *data)
 Create a rotation from a pointer array representing all rotation fields in \(\boldsymbol{q}\in\mathbb{R}^2\).
 
Toperator[] (int i)
 Access a field from \(\boldsymbol{q}\in\mathbb{R}^2\).
 
const Tw () const
 Access the real element of the rotation.
 
const Tx () const
 Access the imaginary element of the rotation.
 
Tw ()
 Access the real element of the rotation.
 
Tx ()
 Access the imaginary element of the rotation.
 
const Vec2T elements () const
 Access all elements of \(\boldsymbol{q}\in\mathbb{R}^2\).
 
Vec2T array () const
 Access all elements of \(\boldsymbol{q}\in\mathbb{R}^2\).
 
Tdata ()
 Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^2\).
 
const Tdata () const
 Access pointer to all elements of \(\boldsymbol{q}\in\mathbb{R}^2\).
 
SO2 copy () const
 Get a deep copy of the current rotation.
 
void normalize ()
 Normalize the elements of \(\boldsymbol{q}\) to make it a valid rotation.
 
SO2 normalized ()
 Obtain a normalized copy of the current rotation.
 
Mat2T R () const
 Convert the rotation to matrix representation \(\begin{bmatrix}\cos\theta & -\sin\theta \\ \sin\theta & \cos\theta\end{bmatrix}\).
 
SO2 inverse () const
 Obtain the inverse rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\).
 
SO2invert ()
 Invert the current rotation \(\boldsymbol{R}_A^B\rightarrow \boldsymbol{R}_B^A\).
 
T angle () const
 Obtain the equivalent scalar angle \(\theta\) of the rotation.
 
template<typename Tout = T, typename T2 >
SO2< Tout > otimes (const SO2< 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 >
SO2< Toutoplus (const Matrix< T2, 1, 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, 1, 1 > ominus (const SO2< T2 > &q) const
 Implementation of group subtraction: \(\boldsymbol{q}_A^B\ominus \boldsymbol{q}_A^{B'} \rightarrow \boldsymbol{\theta}_B^{B'}\).
 
SO2operator= (const SO2 &q)
 Copy constructor.
 
template<typename T2 >
SO2 operator* (const SO2< T2 > &q) const
 Invocation of otimes via multiplication.
 
template<typename T2 >
SO2operator*= (const SO2< T2 > &q)
 Invocation of otimes via multiplication.
 
SO2operator*= (const double &s)
 Scale a rotation by a scalar.
 
SO2operator/= (const double &s)
 Scale a rotation by a scalar.
 
SO2 operator/ (const double &s) const
 Scale a rotation by a scalar.
 
template<typename Tout = T, typename T2 >
Matrix< Tout, 2, 1 > operator* (const Matrix< T2, 2, 1 > &v) const
 Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).
 
Vec2T operator* (const Vec2T &v) const
 Transform a vector via multiplication: \(\boldsymbol{q}_A^B\boldsymbol{t}^A \rightarrow \boldsymbol{t}^B\).
 
SO2 operator+ (const Vec1T &v) const
 Invocation of oplus via addition.
 
SO2operator+= (const Vec1T &v)
 Invocation of oplus via addition.
 
template<typename T2 >
Vec1T operator- (const SO2< T2 > &q) const
 Invocation of ominus via subtraction.
 
template<typename T2 >
SO2< T2cast () const
 Cast the underlying numeric type.
 

Static Public Member Functions

static SO2 random ()
 Obtain a random rotation.
 
static SO2 identity ()
 Obtain an identity \(SO(2)\) rotation.
 
static SO2 nans ()
 Obtain a rotation full of NaNs.
 
static SO2 fromAngle (const T angle)
 Convert an angle (in radians) into a rotation.
 
static SO2 fromR (const Mat2T &m)
 Convert a rotation matrix \(\boldsymbol{R}\in\mathbb{R}^{2\times 2}\) to a \(SO(2)\) rotation.
 
static SO2 fromTwoUnitVectors (const Vec2T &u, const Vec2T &v)
 Given two unit vectors \(\boldsymbol{u},\boldsymbol{v}\in \mathbb{R}^2\), returns the rotation that rotates \(\boldsymbol{u}\rightarrow\boldsymbol{v}\).
 
static SO2 fromComplex (const T qw, const T qx)
 Construct a rotation from the individual fields.
 
static SO2 fromComplex (const Vec2T &qvec)
 Construct a rotation from a rotation fields vector.
 
static Mat2T hat (const Vec1T &omega)
 Hat operator implementation, which coverts the tangent-space vector representation to the corresponding Lie algebra: \(\mathbb{R}\rightarrow \mathfrak{so}(2)\).
 
static Vec1T vee (const Mat2T &Omega)
 Vee operator implementation, which coverts the Lie algebra representation to a tangent-space vector representation: \(\mathfrak{so}(2) \rightarrow \mathbb{R}\).
 
static Mat2T log (const SO2 &q)
 Logarithmic chart map implementation: \(SO(2) \rightarrow \mathfrak{so}(2)\).
 
static Vec1T Log (const SO2 &q)
 Logarithmic chart map implementation: \(SO(2) \rightarrow \mathbb{R}\).
 
static SO2 exp (const Mat2T &Omega)
 Exponential chart map implementation: \(\mathfrak{so}(2) \rightarrow SO(2)\).
 
static SO2 Exp (const Vec1T &omega)
 Exponential chart map implementation: \(\mathbb{R} \rightarrow SO(2)\).
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Map< Vec2T > arr_
 Memory-mapped array representing all rotation fields in \(\boldsymbol{q}\).
 

Detailed Description

template<typename T>
class SO2< T >

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

Constructor & Destructor Documentation

◆ SO2() [1/4]

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

Create a rotation (with garbage data).

◆ SO2() [2/4]

template<typename T >
SO2< T >::SO2 ( const Ref< const Vec2T > & arr)
inline

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

◆ SO2() [3/4]

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

Copy constructor from another rotation.

◆ SO2() [4/4]

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

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

Member Function Documentation

◆ angle()

template<typename T >
T SO2< T >::angle ( ) const
inline

Obtain the equivalent scalar angle \(\theta\) of the rotation.

\(-\pi \leq \theta \leq \pi\).

◆ array()

template<typename T >
Vec2T SO2< T >::array ( ) const
inline

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

◆ cast()

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

Cast the underlying numeric type.

◆ copy()

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

Get a deep copy of the current rotation.

◆ data() [1/2]

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

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

◆ data() [2/2]

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

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

◆ elements()

template<typename T >
const Vec2T SO2< T >::elements ( ) const
inline

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

◆ exp()

template<typename T >
static SO2 SO2< T >::exp ( const Mat2T & Omega)
inlinestatic

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

◆ Exp()

template<typename T >
static SO2 SO2< T >::Exp ( const Vec1T & omega)
inlinestatic

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

◆ fromAngle()

template<typename T >
static SO2 SO2< T >::fromAngle ( const T angle)
inlinestatic

Convert an angle (in radians) into a rotation.

◆ fromComplex() [1/2]

template<typename T >
static SO2 SO2< T >::fromComplex ( const T qw,
const T qx )
inlinestatic

Construct a rotation from the individual fields.

Parameters
qwReal component of the rotation \(\boldsymbol{q}\in SO(2)\).
qxImaginary component of the rotation \(\boldsymbol{q}\in SO(2)\).

◆ fromComplex() [2/2]

template<typename T >
static SO2 SO2< T >::fromComplex ( const Vec2T & qvec)
inlinestatic

Construct a rotation from a rotation fields vector.

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

◆ fromR()

template<typename T >
static SO2 SO2< T >::fromR ( const Mat2T & m)
inlinestatic

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

◆ fromTwoUnitVectors()

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

Given two unit vectors \(\boldsymbol{u},\boldsymbol{v}\in \mathbb{R}^2\), returns the rotation that rotates \(\boldsymbol{u}\rightarrow\boldsymbol{v}\).

◆ hat()

template<typename T >
static Mat2T SO2< T >::hat ( const Vec1T & omega)
inlinestatic

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

◆ identity()

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

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

◆ inverse()

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

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

◆ invert()

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

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

◆ log()

template<typename T >
static Mat2T SO2< T >::log ( const SO2< T > & q)
inlinestatic

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

◆ Log()

template<typename T >
static Vec1T SO2< T >::Log ( const SO2< T > & q)
inlinestatic

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

◆ nans()

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

Obtain a rotation full of NaNs.

◆ normalize()

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

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

◆ normalized()

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

Obtain a normalized copy of the current rotation.

◆ ominus()

template<typename T >
template<typename Tout = T, typename T2 >
Matrix< Tout, 1, 1 > SO2< T >::ominus ( const SO2< 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, 2, 1 > SO2< T >::operator* ( const Matrix< T2, 2, 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 >
SO2 SO2< T >::operator* ( const SO2< T2 > & q) const
inline

Invocation of otimes via multiplication.

◆ operator*() [3/3]

template<typename T >
Vec2T SO2< T >::operator* ( const Vec2T & 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 >
SO2 & SO2< 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 >
SO2 & SO2< T >::operator*= ( const SO2< T2 > & q)
inline

Invocation of otimes via multiplication.

◆ operator+()

template<typename T >
SO2 SO2< T >::operator+ ( const Vec1T & v) const
inline

Invocation of oplus via addition.

◆ operator+=()

template<typename T >
SO2 & SO2< T >::operator+= ( const Vec1T & v)
inline

Invocation of oplus via addition.

◆ operator-()

template<typename T >
template<typename T2 >
Vec1T SO2< T >::operator- ( const SO2< T2 > & q) const
inline

Invocation of ominus via subtraction.

◆ operator/()

template<typename T >
SO2 SO2< 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 >
SO2 & SO2< 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 >
SO2 & SO2< T >::operator= ( const SO2< T > & q)
inline

Copy constructor.

◆ operator[]()

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

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

◆ oplus()

template<typename T >
template<typename Tout = T, typename T2 >
SO2< Tout > SO2< T >::oplus ( const Matrix< T2, 1, 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 >
SO2< Tout > SO2< T >::otimes ( const SO2< T2 > & q) const
inline

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

◆ R()

template<typename T >
Mat2T SO2< T >::R ( ) const
inline

Convert the rotation to matrix representation \(\begin{bmatrix}\cos\theta & -\sin\theta \\ \sin\theta & \cos\theta\end{bmatrix}\).

◆ random()

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

Obtain a random rotation.

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

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

◆ vee()

template<typename T >
static Vec1T SO2< T >::vee ( const Mat2T & Omega)
inlinestatic

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

◆ w() [1/2]

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

Access the real element of the rotation.

◆ w() [2/2]

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

Access the real element of the rotation.

◆ x() [1/2]

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

Access the imaginary element of the rotation.

◆ x() [2/2]

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

Access the imaginary element of the rotation.

Member Data Documentation

◆ arr_

template<typename T >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Map<Vec2T> SO2< T >::arr_

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


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