Skip to content

Class translotator::SOGroup

template <size_t N, typename Type>

ClassList > translotator > SOGroup

Special Orthogonal Group. More...

  • #include <SOGroup.hpp>

Inherits the following classes: translotator::SquareMatrix

Public Types inherited from translotator::MatrixBase

See translotator::MatrixBase

Type Name
typedef Type DATATYPE

Public Static Attributes

Type Name
constexpr static ObjectType OBJECT_TYPE = = ObjectType::SO_GROUP

Public Static Attributes inherited from translotator::SquareMatrix

See translotator::SquareMatrix

Type Name
constexpr static ObjectType OBJECT_TYPE = = ObjectType::SQUARE_MATRIX

Public Static Attributes inherited from translotator::MatrixBase

See translotator::MatrixBase

Type Name
constexpr static size_t COLS = = M
constexpr static bool MATRIX_BASE = = true
constexpr static size_t ROWS = = N

Public Functions

Type Name
SOGroup (const Vector< N, Type > & vec1, const Vector< N, Type > & vec2, bool col=true)
SOGroup (const Vector< N, Type > & vec1, const Vector< N, Type > & vec2, const Vector< N, Type > & vec3, bool col=true)
SOGroup (const Type & theta)
SOGroup (const Vector< N, Type > & angleVector)
SOGroup< N, Type > T () const
transpose
void inverse ()
inverse this matrix
SOGroup< N, Type > inversed () const
inverse is same as transpose in SOGroup __
void normalize ()
normalize this matrix
SOGroup< N, Type > normalized () const
Get the orthogonalized matrix.
auto operator* (const OtherContainer & other) const
SOGroup *SOGroup =>SOGroup .
void operator*= (const SOGroup< N, Type > & other)
SOGroup *=SOGroup .
SquareMatrix< N, Type > operator+ (const OtherContainer & other) const
SOGroup +SOGroup =>SquareMatrix .
SquareMatrix< N, Type > operator- (const OtherContainer & other) const
SOGroup -SOGroup =>SquareMatrix .
SOGroup< N, Type > operator- () const
- SOGroup __
auto operator/ (const OtherContainer & other) const
SOGroup /SOGroup =>SOGroup .
SOGroup< N, Type > pow (const Type & t) const
power of SOGroup . Using Exponential & Logarithm Map of Lie Group
AxisAngle< Type > toAxisAngle () const
convert to AxisAngle __
EulerAngle< Type, NewOrder > toEulerAngle () const
Convert to Euler Angle.
UnitComplexNum< Type > toUnitComplexNum () const
convert to UnitComplexNum . Using only z-axis
UnitQuaternion< Type > toUnitQuaternion () const
convert to UnitQuaternion __

Public Functions inherited from translotator::SquareMatrix

See translotator::SquareMatrix

Type Name
Type determinant () const
determinant of a square matrix. Only 2x2, 3x3 matrices are supported
void inverse ()
SquareMatrix< N, Type > inversed (bool & result) const
1x1 ~ 3x3 closed form solution 4x4 ~ LU factorization with partial pivotting from PX4-Matrix Library
Type trace () const
trace of a square matrix

Public Functions inherited from translotator::MatrixBase

See translotator::MatrixBase

Type Name
MatrixBase () = default
Returns the number of columns.
MatrixBase (const MatrixBase & other) = default
MatrixBase (const Type data)
MatrixBase (const Type data)
MatrixBase (const initializer_list< N *M, Type > & list)
Initializer list constructor.
auto T () const
Transpose.
Matrix< P, Q, Type > block (size_t i, size_t j) const
Returns a block of the matrix.
Matrix< P, Q, Type > block () const
Returns a block of the matrix.
ComplexNum< Type > cast2ComplexNum () const
Casts the object to a complex number by copying.
ComplexNum< Type > & cast2ComplexNumRef ()
Casts the object to a complex number reference without copying.
DualNumber< Type > cast2DualNumber () const
Casts the object to a dual number by copying.
DualNumber< Type > & cast2DualNumberRef ()
Casts the object to a dual number reference without copying.
DualQuaternion< Type > cast2DualQuaternion () const
Casts the object to a dual quaternion by copying.
DualQuaternion< Type > & cast2DualQuaternionRef ()
Casts the object to a dual quaternion reference without copying.
Matrix< N, M, Type > cast2Matrix () const
Casts the object to a different matrix type by copying.
Matrix< N, M, Type > & cast2MatrixRef ()
Casts the object to a matrix reference without copying.
Quaternion< Type > cast2Quaternion () const
Casts the object to a quaternion by copying.
Quaternion< Type > & cast2QuaternionRef ()
Casts the object to a quaternion reference without copying.
SOGroup< N, Type > cast2SOGroup () const
Casts the object to a special orthogonal group by copying.
SOGroup< N, Type > & cast2SOGroupRef ()
Casts the object to a special orthogonal group reference without copying.
SquareMatrix< N, Type > cast2SquareMatrix () const
Casts the object to a square matrix by copying.
SquareMatrix< N, Type > & cast2SquareMatrixRef ()
Casts the object to a square matrix reference without copying.
UnitComplexNum< Type > cast2UnitComplexNum () const
Casts the object to a unit complex number by copying.
UnitComplexNum< Type > & cast2UnitComplexNumRef ()
Casts the object to a unit complex number reference without copying.
UnitDualQuaternion< Type > cast2UnitDualQuaternion () const
Casts the object to a unit dual quaternion by copying.
UnitDualQuaternion< Type > & cast2UnitDualQuaternionRef ()
Casts the object to a unit dual quaternion reference without copying.
UnitQuaternion< Type > cast2UnitQuaternion () const
Casts the object to a unit quaternion by copying.
UnitQuaternion< Type > & cast2UnitQuaternionRef ()
Casts the object to a unit quaternion reference without copying.
Vector< N, Type > cast2Vector () const
Casts the object to a vector by copying.
Vector< N, Type > & cast2VectorRef ()
Casts the object to a vector reference without copying.
NewContainer castContainer () const
Casts the matrix to a different container type by copying.
NewContainer & castContainerRef ()
Casts the object to a different container reference without copying.
NewDerived & castContainerRef ()
auto castDataType () const
Returns the Frobenius norm.
Matrix< N, 1, Type > col (size_t j) const
Returns the j-th column.
void copyTo (Type * data) const
Returns the raw data pointer.
void fill (const Type & v)
Fills the matrix with a value.
Type frobeniusNorm () const
Type frobeniusNormSquared () const
Returns the squared Frobenius norm.
Type * getData () const
const Type & operator() (size_t i, size_t j) const
Accesses the element at (i, j)
Type & operator() (size_t i, size_t j)
Accesses the element at (i, j)
auto operator* (const OtherDerived & other) const
Matrix multiplication.
Derived operator* (const Type & v) const
Matrix multiplication by scalar.
void operator*= (const OtherDerived & other)
Matrix multiplication by scalar.
Derived operator+ (const OtherDerived & other) const
Multiplication by scalar.
void operator+= (const OtherDerived & other)
Matrix division by scalar.
Derived operator- (const OtherDerived & other) const
Matrix subtraction.
Derived operator- () const
Matrix multiplication by scalar.
void operator-= (const OtherDerived & other)
Matrix subtraction by scalar.
Derived operator/ (Type v) const
Division by scalar.
void operator/= (Type v)
Division by scalar.
Derived & operator= (const Derived & other)
Copies the data to the given pointer.
void print () const
Prints the matrix.
Matrix< 1, M, Type > row (size_t i) const
Returns the i-th row.
Derived & setBlock (size_t i, size_t j, const OtherDerived & block)
Sets the element at (i, j)
Derived & setBlock (const OtherDerived & block)
Sets the i-th row.
Derived & setCol (size_t j, const OtherDerived & col)
Sets the j-th column.
Derived & setCol (const OtherDerived & col)
Sets the j-th column.
Derived & setRow (size_t i, const OtherDerived & row)
Sets the i-th row.
Derived & setRow (const OtherDerived & row)
Sets the i-th row.
void swapCols (size_t j1, size_t j2)
Swaps two columns.
void swapRows (size_t i1, size_t i2)
Swaps two rows.
Type toScalar () const
Casts the matrix to a scalar if it is a 1x1 matrix.

Public Static Functions

Type Name
SOGroup< N, Type > axisRotation (const Type & angle)
Create a rotation matrix around the axis.
SOGroup< N, Type > identity ()
identity rotation element, which is identity matrix

Public Static Functions inherited from translotator::MatrixBase

See translotator::MatrixBase

Type Name
Derived NaN ()
Returns a matrix filled with NaN.
constexpr static size_t colSize ()
Returns the number of rows.
Derived eye ()
Returns an identity matrix.
Derived ones ()
Returns a matrix filled with ones.
constexpr static size_t rowSize ()
Derived zeros ()
Returns a matrix filled with zeros.

Protected Attributes inherited from translotator::MatrixBase

See translotator::MatrixBase

Type Name
Type data_

Detailed Description

Template parameters:

  • N dimension
  • Type data type

Special Orthogonal Group is a group of rotation in N dimension. It is a group of orthogonal matrices with determinant 1. Subgroup of SOGroup is SO(2) and SO(3). Also SOGroup is a Lie Group. Exponential and Logarithm map can be defined.

Public Static Attributes Documentation

variable OBJECT_TYPE

constexpr static ObjectType translotator::SOGroup< N, Type >::OBJECT_TYPE;

Public Functions Documentation

function SOGroup [2/5]

template<size_t N_, typename>
inline translotator::SOGroup::SOGroup (
    const Vector < N, Type > & vec1,
    const Vector < N, Type > & vec2,
    bool col=true
) 

constructors


function SOGroup [3/5]

template<size_t N_, typename>
inline translotator::SOGroup::SOGroup (
    const Vector < N, Type > & vec1,
    const Vector < N, Type > & vec2,
    const Vector < N, Type > & vec3,
    bool col=true
) 

function SOGroup [4/5]

template<size_t N_, typename>
inline explicit translotator::SOGroup::SOGroup (
    const Type & theta
) 

function SOGroup [5/5]

template<size_t N_, typename>
inline explicit translotator::SOGroup::SOGroup (
    const Vector < N, Type > & angleVector
) 

function T

inline SOGroup < N, Type > translotator::SOGroup::T () const

function inverse

inline void translotator::SOGroup::inverse () 

function inversed

inline SOGroup < N, Type > translotator::SOGroup::inversed () const

function normalize

inline void translotator::SOGroup::normalize () 

function normalized

Get the orthogonalized matrix.

inline SOGroup < N, Type > translotator::SOGroup::normalized () const

utils

Returns:

SOGroup<N, Type>

Note:

This function uses UnitComplexNum & UnitQuternion internally. Not a mathmatically correct way, but it works.


function operator*

SOGroup *SOGroup =>SOGroup .

template<typename OtherContainer>
inline auto translotator::SOGroup::operator* (
    const OtherContainer & other
) const

Template parameters:


function operator*=

inline void translotator::SOGroup::operator*= (
    const SOGroup < N, Type > & other
) 

function operator+

SOGroup +SOGroup =>SquareMatrix .

template<typename OtherContainer>
inline SquareMatrix < N, Type > translotator::SOGroup::operator+ (
    const OtherContainer & other
) const

operators

Template parameters:

  • OtherContainer Matrix based object with same dimension

function operator-

SOGroup -SOGroup =>SquareMatrix .

template<typename OtherContainer>
inline SquareMatrix < N, Type > translotator::SOGroup::operator- (
    const OtherContainer & other
) const

Template parameters:


function operator-

inline SOGroup < N, Type > translotator::SOGroup::operator- () const

function operator/

SOGroup /SOGroup =>SOGroup .

template<typename OtherContainer>
inline auto translotator::SOGroup::operator/ (
    const OtherContainer & other
) const

Template parameters:

  • OtherContainer Matrix based object with same dimension

function pow

inline SOGroup < N, Type > translotator::SOGroup::pow (
    const Type & t
) const

function toAxisAngle

inline AxisAngle < Type > translotator::SOGroup::toAxisAngle () const

function toEulerAngle

Convert to Euler Angle.

template<EULER_ORDER NewOrder>
inline EulerAngle < Type, NewOrder > translotator::SOGroup::toEulerAngle () const

Template parameters:

  • NewOrder New Euler Order

function toUnitComplexNum

convert to UnitComplexNum . Using only z-axis

inline UnitComplexNum < Type > translotator::SOGroup::toUnitComplexNum () const

casts


function toUnitQuaternion

inline UnitQuaternion < Type > translotator::SOGroup::toUnitQuaternion () const

Public Static Functions Documentation

function axisRotation

Create a rotation matrix around the axis.

template<AXIS Axis>
static inline SOGroup < N, Type > translotator::SOGroup::axisRotation (
    const Type & angle
) 

Template parameters:

  • Axis Axis to rotate

Parameters:

  • angle angle in radian

function identity

identity rotation element, which is identity matrix

static inline SOGroup < N, Type > translotator::SOGroup::identity () 

static functions


Friends Documentation

friend operator*

inline SquareMatrix < N, Type > translotator::SOGroup::operator* (
    const Type & lhs,
    const SOGroup & rhs
) 


The documentation for this class was generated from the following file include/translotator/objects/SOGroup.hpp