Geomi
Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
SO3::Group< T_SCALAR_TYPE > Class Template Reference

#include <SO3_Group.hpp>

Inheritance diagram for SO3::Group< T_SCALAR_TYPE >:
Inheritance graph
[legend]
Collaboration diagram for SO3::Group< T_SCALAR_TYPE >:
Collaboration graph
[legend]

Public Member Functions

 Group (const Group< T_SCALAR_TYPE > &g)
 
 Group (const Eigen::Quaternion< T_SCALAR_TYPE > &q_)
 
 Group (const T_SCALAR_TYPE &w, const T_SCALAR_TYPE &x, const T_SCALAR_TYPE &y, const T_SCALAR_TYPE &z)
 
 Group (const T_SCALAR_TYPE *data)
 
template<class Derived >
 Group (const Eigen::QuaternionBase< Derived > &other)
 
 Group (const Eigen::AngleAxis< T_SCALAR_TYPE > &aa)
 
template<typename Derived >
 Group (const Eigen::MatrixBase< Derived > &other)
 
template<class OtherScalar , int OtherOptions>
 Group (const Eigen::Quaternion< OtherScalar, OtherOptions > &other)
 
Eigen::Quaternion< T_SCALAR_TYPE > q () const
 
void q (const Eigen::Quaternion< T_SCALAR_TYPE > &q_)
 
void q (const T_SCALAR_TYPE &w, const T_SCALAR_TYPE &x, const T_SCALAR_TYPE &y, const T_SCALAR_TYPE &z)
 
void q (const T_SCALAR_TYPE *data)
 
template<class Derived >
void q (const Eigen::QuaternionBase< Derived > &other)
 
void q (const Eigen::AngleAxis< T_SCALAR_TYPE > &aa)
 
template<typename Derived >
void q (const Eigen::MatrixBase< Derived > &other)
 
template<class OtherScalar , int OtherOptions>
void q (const Eigen::Quaternion< OtherScalar, OtherOptions > &other)
 
Group< T_SCALAR_TYPE > inverse () const
 
void operator*= (Group< T_SCALAR_TYPE > const &g)
 
Group< T_SCALAR_TYPE > operator* (Group< T_SCALAR_TYPE > const &g) const
 
Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > transformVector (const Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > &v) const
 
Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > operator* (Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > const &v) const
 
Eigen::Matrix< T_SCALAR_TYPE, 3, 3 > toRotationMatrix () const
 
Eigen::Matrix< T_SCALAR_TYPE, 3, 3 > toAxisAngle () const
 
Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > toVector () const
 
bool isApprox (Group< T_SCALAR_TYPE > const &g) const
 
- Public Member Functions inherited from LieGroupBase< Group< T_SCALAR_TYPE >, 3 >
Group< T_SCALAR_TYPE > inverse () const
 
void inverted ()
 
void operator*= (Group< T_SCALAR_TYPE > const &g)
 
NOXVector< T_DOF > toNOXVector () const
 
- Public Member Functions inherited from CRTP< Group< T_SCALAR_TYPE > >
Group< T_SCALAR_TYPE > & underlying ()
 
Group< T_SCALAR_TYPE > const & underlying () const
 

Static Public Member Functions

static Group< T_SCALAR_TYPE > Identity ()
 
- Static Public Member Functions inherited from LieGroupBase< Group< T_SCALAR_TYPE >, 3 >
static Group< T_SCALAR_TYPE > Identity ()
 
static const unsigned int dof ()
 

Protected Attributes

Eigen::Quaternion< T_SCALAR_TYPE > m_q
 

Additional Inherited Members

- Static Public Attributes inherited from LieGroupBase< Group< T_SCALAR_TYPE >, 3 >
static const unsigned int DOF
 

Detailed Description

template<typename T_SCALAR_TYPE>
class SO3::Group< T_SCALAR_TYPE >

Class for Lie group \(SO(3)\) implementation.

Template Parameters
T_SCALAR_TYPEFloating point type used for internal representation of coefficients.

Member Function Documentation

◆ Identity()

template<typename T_SCALAR_TYPE>
static Group<T_SCALAR_TYPE> SO3::Group< T_SCALAR_TYPE >::Identity ( )
inlinestatic
Returns
the element representing the group identity for operation *.

◆ inverse()

template<typename T_SCALAR_TYPE>
Group<T_SCALAR_TYPE> SO3::Group< T_SCALAR_TYPE >::inverse ( ) const
inline
Returns
the group inverse of *this.

◆ operator*() [1/2]

template<typename T_SCALAR_TYPE>
Group<T_SCALAR_TYPE> SO3::Group< T_SCALAR_TYPE >::operator* ( Group< T_SCALAR_TYPE > const &  g) const
inline

Implements the group operation on \(SO(3)\). The * operator has been chosen instead of the + operator since the usual matrix and quaternion representations of rotations are groups defined with a natural mutliplication operation.

Returns
the group addition of *this and g.

◆ operator*() [2/2]

template<typename T_SCALAR_TYPE>
Eigen::Matrix<T_SCALAR_TYPE,3,1> SO3::Group< T_SCALAR_TYPE >::operator* ( Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > const &  v) const
inline

Implements the product of the matrix representation of the rotation *this and the voctor v.

Returns
the transformation of the \(\mathbb R^3\) vector v by the rotation represented by *this.

◆ q()

template<typename T_SCALAR_TYPE>
Eigen::Quaternion<T_SCALAR_TYPE> SO3::Group< T_SCALAR_TYPE >::q ( ) const
inline
Returns
the quaternion representation of the rotation.

◆ toAxisAngle()

template<typename T_SCALAR_TYPE>
Eigen::Matrix<T_SCALAR_TYPE,3,3> SO3::Group< T_SCALAR_TYPE >::toAxisAngle ( ) const
inline
Returns
the axis-angle representation of the rotation.

◆ toRotationMatrix()

template<typename T_SCALAR_TYPE>
Eigen::Matrix<T_SCALAR_TYPE,3,3> SO3::Group< T_SCALAR_TYPE >::toRotationMatrix ( ) const
inline
Returns
the 3 by 3 matrix representation of the rotation.

◆ toVector()

template<typename T_SCALAR_TYPE>
Eigen::Matrix<T_SCALAR_TYPE,3,1> SO3::Group< T_SCALAR_TYPE >::toVector ( ) const
inline
Returns
the vector representation of the rotation, that is the vector \(\vec v\) such that the rotation of any given vector \(\vec u\) is the result of \(vec v\wedge\vec u\).

◆ transformVector()

template<typename T_SCALAR_TYPE>
Eigen::Matrix<T_SCALAR_TYPE,3,1> SO3::Group< T_SCALAR_TYPE >::transformVector ( const Eigen::Matrix< T_SCALAR_TYPE, 3, 1 > &  v) const
inline
Returns
the transformation of the \(\mathbb R^3\) vector v by the rotation represented by *this.

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