TooN::SE3< Precision > Class Template Reference
[Transformation matrices]

#include <se3.h>

List of all members.

Public Member Functions

template<int R, int C, typename P2 , typename Accessor >
Matrix< 6, 6, Precision > adjoint (const Matrix< R, C, P2, Accessor > &M) const
template<int S, typename P2 , typename Accessor >
Vector< 6, Precision > adjoint (const Vector< S, P2, Accessor > &vect) const
template<int S, typename P , typename VA >
SE3< Precision > exp (const Vector< S, P, VA > &mu)
const SO3< Precision > & get_rotation () const
SO3< Precision > & get_rotation ()
 Returns the rotation part of the transformation as a SO3.
const Vector< 3, Precision > & get_translation () const
Vector< 3, Precision > & get_translation ()
 Returns the translation part of the transformation as a Vector.
SE3 inverse () const
SE3left_multiply_by (const SE3 &left)
Vector< 6, Precision > ln () const
SE3 operator* (const SE3 &rhs) const
SE3operator*= (const SE3 &rhs)
template<class IP , int S, typename P , typename A >
 SE3 (const Operator< Internal::Identity< IP > > &, const Vector< S, P, A > &T)
template<int S, typename P , typename A >
 SE3 (const Vector< S, P, A > &v)
template<int S, typename P , typename A >
 SE3 (const SO3< Precision > &R, const Vector< S, P, A > &T)
 SE3 ()
 Default constructor. Initialises the the rotation to zero (the identity) and the translation to zero.
template<int R, int C, typename P2 , typename Accessor >
Matrix< 6, 6, Precision > trinvadjoint (const Matrix< R, C, P2, Accessor > &M) const
template<int S, typename P2 , typename Accessor >
Vector< 6, Precision > trinvadjoint (const Vector< S, P2, Accessor > &vect) const

Static Public Member Functions

template<int S, typename P , typename A >
static SE3 exp (const Vector< S, P, A > &vect)
static Matrix< 4, 4, Precision > generator (int i)
template<typename Base >
static Vector< 4, Precision > generator_field (int i, const Vector< 4, Precision, Base > &pos)
 Returns the i-th generator times pos.
static Vector< 6, Precision > ln (const SE3 &se3)

Private Attributes

SO3< Precision > my_rotation
Vector< 3, Precision > my_translation

Related Functions

(Note that these are not member functions.)



template<int Rows, int C, typename PM , typename A , typename P >
Matrix< Rows, 4, typename
Internal::MultiplyType< PM, P >
::type > 
operator* (const Matrix< Rows, C, PM, A > &lhs, const SE3< P > &rhs)
template<int R, int Cols, typename PM , typename A , typename P >
Matrix< 4, Cols, typename
Internal::MultiplyType< P, PM >
::type > 
operator* (const SE3< P > &lhs, const Matrix< R, Cols, PM, A > &rhs)
template<int S, typename PV , typename A , typename P >
Vector< 4, typename
Internal::MultiplyType< P, PV >
::type > 
operator* (const Vector< S, PV, A > &lhs, const SE3< P > &rhs)
template<typename PV , typename A , typename P >
Vector< 3, typename
Internal::MultiplyType< P, PV >
::type > 
operator* (const SE3< P > &lhs, const Vector< 3, PV, A > &rhs)
template<int S, typename PV , typename A , typename P >
Vector< 4, typename
Internal::MultiplyType< P, PV >
::type > 
operator* (const SE3< P > &lhs, const Vector< S, PV, A > &rhs)
template<typename Precision >
std::ostream & operator<< (std::ostream &os, const SE3< Precision > &rhs)

Detailed Description

template<typename Precision = double>
class TooN::SE3< Precision >

Represent a three-dimensional Euclidean transformation (a rotation and a translation). This can be represented by a matrix operating on a homogeneous co-ordinate, so that a vector $\underline{x}$ is transformed to a new location $\underline{x}'$ by

\[\begin{aligned}\underline{x}' &= E\times\underline{x}\\ \begin{bmatrix}x'\\y'\\z'\end{bmatrix} &= \begin{pmatrix}r_{11} & r_{12} & r_{13} & t_1\\r_{21} & r_{22} & r_{23} & t_2\\r_{31} & r_{32} & r_{33} & t_3\end{pmatrix}\begin{bmatrix}x\\y\\z\\1\end{bmatrix}\end{aligned}\]

This transformation is a member of the Special Euclidean Lie group SE3. These can be parameterised six numbers (in the space of the Lie Algebra). In this class, the first three parameters are a translation vector while the second three are a rotation vector, whose direction is the axis of rotation and length the amount of rotation (in radians), as for SO3

Definition at line 50 of file se3.h.


Constructor & Destructor Documentation

template<typename Precision = double>
TooN::SE3< Precision >::SE3 (  )  [inline]

Default constructor. Initialises the the rotation to zero (the identity) and the translation to zero.

Definition at line 53 of file se3.h.

template<typename Precision = double>
template<int S, typename P , typename A >
TooN::SE3< Precision >::SE3 ( const SO3< Precision > &  R,
const Vector< S, P, A > &  T 
) [inline]

Definition at line 56 of file se3.h.

template<typename Precision = double>
template<int S, typename P , typename A >
TooN::SE3< Precision >::SE3 ( const Vector< S, P, A > &  v  )  [inline]

Definition at line 58 of file se3.h.

template<typename Precision = double>
template<class IP , int S, typename P , typename A >
TooN::SE3< Precision >::SE3 ( const Operator< Internal::Identity< IP > > &  ,
const Vector< S, P, A > &  T 
) [inline]

Definition at line 61 of file se3.h.


Member Function Documentation

template<typename Precision >
template<int R, int C, typename P2 , typename Accessor >
Matrix< 6, 6, Precision > TooN::SE3< Precision >::adjoint ( const Matrix< R, C, P2, Accessor > &  M  )  const [inline]

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 190 of file se3.h.

template<typename Precision >
template<int S, typename P2 , typename Accessor >
Vector< 6, Precision > TooN::SE3< Precision >::adjoint ( const Vector< S, P2, Accessor > &  vect  )  const [inline]

Transfer a matrix in the Lie Algebra from one co-ordinate frame to another. This is the operation such that for a matrix $ B $, $ e^{\text{Adj}(v)} = Be^{v}B^{-1} $

Parameters:
M The Matrix to transfer

Definition at line 165 of file se3.h.

template<typename Precision = double>
template<int S, typename P , typename VA >
SE3<Precision> TooN::SE3< Precision >::exp ( const Vector< S, P, VA > &  mu  )  [inline]

Definition at line 387 of file se3.h.

template<typename Precision = double>
template<int S, typename P , typename A >
static SE3 TooN::SE3< Precision >::exp ( const Vector< S, P, A > &  vect  )  [inline, static]

Exponentiate a Vector in the Lie Algebra to generate a new SE3. See the Detailed Description for details of this vector.

Parameters:
vect The Vector to exponentiate
template<typename Precision = double>
static Matrix<4,4,Precision> TooN::SE3< Precision >::generator ( int  i  )  [inline, static]

Definition at line 109 of file se3.h.

template<typename Precision = double>
template<typename Base >
static Vector<4,Precision> TooN::SE3< Precision >::generator_field ( int  i,
const Vector< 4, Precision, Base > &  pos 
) [inline, static]

Returns the i-th generator times pos.

Definition at line 122 of file se3.h.

template<typename Precision = double>
const SO3<Precision>& TooN::SE3< Precision >::get_rotation (  )  const [inline]

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 66 of file se3.h.

template<typename Precision = double>
SO3<Precision>& TooN::SE3< Precision >::get_rotation (  )  [inline]

Returns the rotation part of the transformation as a SO3.

Definition at line 64 of file se3.h.

template<typename Precision = double>
const Vector<3, Precision>& TooN::SE3< Precision >::get_translation (  )  const [inline]

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 71 of file se3.h.

template<typename Precision = double>
Vector<3, Precision>& TooN::SE3< Precision >::get_translation (  )  [inline]

Returns the translation part of the transformation as a Vector.

Definition at line 69 of file se3.h.

template<typename Precision = double>
SE3 TooN::SE3< Precision >::inverse (  )  const [inline]

Definition at line 86 of file se3.h.

template<typename Precision = double>
SE3& TooN::SE3< Precision >::left_multiply_by ( const SE3< Precision > &  left  )  [inline]

Definition at line 103 of file se3.h.

template<typename Precision = double>
Vector<6, Precision> TooN::SE3< Precision >::ln (  )  const [inline]

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 84 of file se3.h.

template<typename Precision >
Vector< 6, Precision > TooN::SE3< Precision >::ln ( const SE3< Precision > &  se3  )  [inline, static]

Take the logarithm of the matrix, generating the corresponding vector in the Lie Algebra. See the Detailed Description for details of this vector.

Definition at line 423 of file se3.h.

template<typename Precision = double>
SE3 TooN::SE3< Precision >::operator* ( const SE3< Precision > &  rhs  )  const [inline]

Right-multiply by another SE3 (concatenate the two transformations)

Parameters:
rhs The multipier

Definition at line 101 of file se3.h.

template<typename Precision = double>
SE3& TooN::SE3< Precision >::operator*= ( const SE3< Precision > &  rhs  )  [inline]

Right-multiply by another SE3 (concatenate the two transformations)

Parameters:
rhs The multipier

Definition at line 93 of file se3.h.

template<typename Precision >
template<int R, int C, typename P2 , typename Accessor >
Matrix< 6, 6, Precision > TooN::SE3< Precision >::trinvadjoint ( const Matrix< R, C, P2, Accessor > &  M  )  const [inline]

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 206 of file se3.h.

template<typename Precision >
template<int S, typename P2 , typename Accessor >
Vector< 6, Precision > TooN::SE3< Precision >::trinvadjoint ( const Vector< S, P2, Accessor > &  vect  )  const [inline]

Transfer covectors between frames (using the transpose of the inverse of the adjoint) so that trinvadjoint(vect1) * adjoint(vect2) = vect1 * vect2

Definition at line 179 of file se3.h.


Friends And Related Function Documentation

template<int Rows, int C, typename PM , typename A , typename P >
Matrix< Rows, 4, typename Internal::MultiplyType< PM, P >::type > operator* ( const Matrix< Rows, C, PM, A > &  lhs,
const SE3< P > &  rhs 
) [related]

Left-multiply by a Matrix

Definition at line 381 of file se3.h.

template<int R, int Cols, typename PM , typename A , typename P >
Matrix< 4, Cols, typename Internal::MultiplyType< P, PM >::type > operator* ( const SE3< P > &  lhs,
const Matrix< R, Cols, PM, A > &  rhs 
) [related]

Right-multiply by a Matrix

Definition at line 347 of file se3.h.

template<int S, typename PV , typename A , typename P >
Vector< 4, typename Internal::MultiplyType< P, PV >::type > operator* ( const Vector< S, PV, A > &  lhs,
const SE3< P > &  rhs 
) [related]

Left-multiply by a Vector

Definition at line 313 of file se3.h.

template<typename PV , typename A , typename P >
Vector< 3, typename Internal::MultiplyType< P, PV >::type > operator* ( const SE3< P > &  lhs,
const Vector< 3, PV, A > &  rhs 
) [related]

Right-multiply by a Vector

Definition at line 279 of file se3.h.

template<int S, typename PV , typename A , typename P >
Vector< 4, typename Internal::MultiplyType< P, PV >::type > operator* ( const SE3< P > &  lhs,
const Vector< S, PV, A > &  rhs 
) [related]

Right-multiply by a Vector

Definition at line 272 of file se3.h.

template<typename Precision >
std::ostream & operator<< ( std::ostream &  os,
const SE3< Precision > &  rhs 
) [related]

Write an SE3 to a stream

Definition at line 223 of file se3.h.


Member Data Documentation

template<typename Precision = double>
SO3<Precision> TooN::SE3< Precision >::my_rotation [private]

Definition at line 156 of file se3.h.

template<typename Precision = double>
Vector<3, Precision> TooN::SE3< Precision >::my_translation [private]

Definition at line 157 of file se3.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


libtoon
Author(s): Florian Weisshardt
autogenerated on Fri Jan 11 10:09:50 2013