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

Represent a three-dimensional Euclidean transformation (a rotation and a translation). More...

#include <se3.h>

List of all members.

Public Member Functions

 SE3 ()
template<int S, typename P, typename A>
 SE3 (const SO3< Precision > &R, const Vector< S, P, A > &T)
template<int S, typename P, typename A>
 SE3 (const Vector< S, P, A > &v)
SO3< Precision > & get_rotation ()
const SO3< Precision > & get_rotation () const
Vector< 3, Precision > & get_translation ()
const Vector< 3,
Precision > & 
get_translation () const
Vector< 6, Precision > ln () const
SE3 inverse () const
SE3operator *= (const SE3 &rhs)
SE3 operator * (const SE3 &rhs) const
SE3left_multiply_by (const SE3 &left)
template<int S, typename Accessor>
Vector< 6, Precision > adjoint (const Vector< S, Precision, Accessor > &vect) const
template<int S, typename Accessor>
Vector< 6, Precision > trinvadjoint (const Vector< S, Precision, Accessor > &vect) const
template<int R, int C, typename Accessor>
Matrix< 6, 6, Precision > adjoint (const Matrix< R, C, Precision, Accessor > &M) const
template<int R, int C, typename Accessor>
Matrix< 6, 6, Precision > trinvadjoint (const Matrix< R, C, Precision, Accessor > &M) const

Static Public Member Functions

template<int S, typename P, typename A>
static SE3 exp (const Vector< S, P, A > &vect)
static Vector< 6,
Precision > 
ln (const SE3 &se3)
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)

Related Functions

(Note that these are not member functions.)

template<typename Precision>
std::ostream & operator<< (std::ostream &os, const SE3< Precision > &rhs)
template<typename Precision>
std::istream & operator>> (std::istream &is, SE3< Precision > &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 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 Vector< S, PV, 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 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)


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


Constructor & Destructor Documentation

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

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


Member Function Documentation

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

Returns the rotation part of the transformation as a SO3.

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

Returns the translation part of the transformation as a Vector.

template<typename Precision>
template<int S, typename P, typename VA>
SE3< Precision > TooN::SE3< Precision >::exp ( const Vector< S, P, VA > &  vect  )  [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>
Vector< 6, Precision > TooN::SE3< Precision >::ln ( const SE3< Precision > &  se3  )  [static]

Take the logarithm of the matrix, generating the corresponding vector in the Lie Algebra.

See the Detailed Description for details of this vector.

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

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

Parameters:
rhs The multipier

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

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

Parameters:
rhs The multipier

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

Returns the i-th generator times pos.

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

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

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

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


Friends And Related Function Documentation

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

Write an SE3 to a stream.

template<typename Precision>
std::istream & operator>> ( std::istream &  is,
SE3< Precision > &  rhs 
) [related]

Reads an SE3 from a stream.

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.

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.

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.

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.

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.


Generated on Thu May 7 20:28:41 2009 for TooN by  doxygen 1.5.3