Represent a two-dimensional Euclidean transformation (a rotation and a translation).
More...
|
| SE2 () |
| Default constructor. Initialises the the rotation to zero (the identity) and the translation to zero.
|
|
template<class A > |
| SE2 (const SO2< Precision > &R, const Vector< 2, Precision, A > &T) |
|
template<int S, class P , class A > |
| SE2 (const Vector< S, P, A > &v) |
|
SO2< Precision > & | get_rotation () |
| Returns the rotation part of the transformation as a SO2.
|
|
const SO2< Precision > & | get_rotation () const |
|
Vector< 2, Precision > & | get_translation () |
| Returns the translation part of the transformation as a Vector.
|
|
const Vector< 2, Precision > & | get_translation () const |
|
Vector< 3, Precision > | ln () const |
|
SE2 | inverse () const |
| compute the inverse of the transformation
|
|
template<typename P > |
SE2< typename Internal::MultiplyType< Precision, P >::type > | operator* (const SE2< P > &rhs) const |
| Right-multiply by another SE2 (concatenate the two transformations) More...
|
|
template<typename P > |
SE2 & | operator*= (const SE2< P > &rhs) |
| Self right-multiply by another SE2 (concatenate the two transformations) More...
|
|
template<typename Accessor > |
Vector< 3, Precision > | adjoint (const Vector< 3, Precision, Accessor > &vect) const |
| transfers a vector in the Lie algebra, from one coord frame to another so that exp(adjoint(vect)) = (*this) * exp(vect) * (this->inverse())
|
|
template<typename Accessor > |
Matrix< 3, 3, Precision > | adjoint (const Matrix< 3, 3, Precision, Accessor > &M) const |
|
template<int S, typename PV , typename Accessor > |
SE2< Precision > | exp (const Vector< S, PV, Accessor > &mu) |
|
|
template<int S, typename P , typename A > |
static SE2 | exp (const Vector< S, P, A > &vect) |
| Exponentiate a Vector in the Lie Algebra to generate a new SE2. More...
|
|
static Vector< 3, Precision > | ln (const SE2 &se2) |
| Take the logarithm of the matrix, generating the corresponding vector in the Lie Algebra. More...
|
|
static Matrix< 3, 3, Precision > | generator (int i) |
| returns the generators for the Lie group. More...
|
|
|
(Note that these are not member functions.)
|
template<class Precision > |
std::ostream & | operator<< (std::ostream &os, const SE2< Precision > &rhs) |
| Write an SE2 to a stream. More...
|
|
template<class Precision > |
std::istream & | operator>> (std::istream &is, SE2< Precision > &rhs) |
| Read an SE2 from a stream. More...
|
|
template<int S, typename P , typename PV , typename A > |
Vector< 3, typename Internal::MultiplyType< P, PV >::type > | operator* (const SE2< P > &lhs, const Vector< S, PV, A > &rhs) |
| Right-multiply with a Vector<3> More...
|
|
template<typename P , typename PV , typename A > |
Vector< 2, typename Internal::MultiplyType< P, PV >::type > | operator* (const SE2< P > &lhs, const Vector< 2, PV, A > &rhs) |
| Right-multiply with a Vector<2> (special case, extended to be a homogeneous vector) More...
|
|
template<int S, typename P , typename PV , typename A > |
Vector< 3, typename Internal::MultiplyType< PV, P >::type > | operator* (const Vector< S, PV, A > &lhs, const SE2< P > &rhs) |
| Left-multiply with a Vector<3> More...
|
|
template<int R, int Cols, typename PM , typename A , typename P > |
Matrix< 3, Cols, typename Internal::MultiplyType< P, PM >::type > | operator* (const SE2< P > &lhs, const Matrix< R, Cols, PM, A > &rhs) |
| Right-multiply with a Matrix<3> More...
|
|
template<int Rows, int C, typename PM , typename A , typename P > |
Matrix< Rows, 3, typename Internal::MultiplyType< PM, P >::type > | operator* (const Matrix< Rows, C, PM, A > &lhs, const SE2< P > &rhs) |
| Left-multiply with a Matrix<3> More...
|
|
template<typename Precision = DefaultPrecision>
class TooN::SE2< Precision >
Represent a two-dimensional Euclidean transformation (a rotation and a translation).
This can be represented by a \(2\times 3\) 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'\end{bmatrix} &= \begin{pmatrix}r_{11} & r_{12} & t_1\\r_{21} & r_{22} & t_2\end{pmatrix}\begin{bmatrix}x\\y\\1\end{bmatrix}\end{aligned}\]
This transformation is a member of the Special Euclidean Lie group SE2. These can be parameterised with three numbers (in the space of the Lie Algebra). In this class, the first two parameters are a translation vector while the third is the amount of rotation in the plane as for SO2.