14 #ifndef ECL_GEOMETRY_POSE2D_HPP_    15 #define ECL_GEOMETRY_POSE2D_HPP_    21 #include <ecl/linear_algebra.hpp>    23 #include <ecl/config/macros.hpp>    24 #include <ecl/formatters.hpp>    25 #include <ecl/math/constants.hpp>    26 #include <ecl/exceptions/standard_exception.hpp>    27 #include <ecl/mpl/enable_if.hpp>    28 #include <ecl/type_traits/traits.hpp>    29 #include <ecl/type_traits/fundamental_types.hpp>    53 template <
typename Float, enum Pose2DStorageType Storage, 
typename Enable> 
class Pose2D;
    61 template <
typename Float, enum Pose2DStorageType Storage, 
typename Enable>
    67 template <
typename Float, 
typename Enable>
    77 template <
typename Float, 
typename Enable>
    92 template <
typename Float, enum Pose2DStorageType Storage> 
class Pose2DMath {};
   100 template <
typename Float>
   101 class ECL_PUBLIC Pose2DMath<Float,RotationMatrixStorage> {
   103         typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrixType; 
   105         static RotationMatrixType Identity() { 
return RotationMatrixType::Identity(); } 
   106         static RotationMatrixType Rotation(
const RotationMatrixType &rotation) { 
return rotation; } 
   107         static RotationMatrixType Rotation(
const Angle<Float>& angle) { 
return angle.rotationMatrix(); }  
   109         static RotationMatrixType Product(
const RotationMatrixType &rot1, 
const RotationMatrixType &rot2) { 
return rot1*rot2; } 
   110         static RotationMatrixType Product(
const RotationMatrixType &rotation, 
const Angle<Float> &angle) { 
return rotation*angle.rotationMatrix(); } 
   111         static RotationMatrixType Inverse(
const RotationMatrixType &rotation) { 
return rotation.transpose(); } 
   121 template <
typename Float>
   122 class ECL_PUBLIC Pose2DMath<Float,RotationAngleStorage> {
   124         typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrixType; 
   127         static Angle<Float> Rotation(
const RotationMatrixType &rotation) { 
return Pose2DMath<Float,RotationMatrixStorage>::Heading(rotation); } 
   145 template <
class Float, enum Pose2DStorageType Storage = RotationMatrixStorage, 
typename Enable = 
void>
   168 template<
typename Float, enum Pose2DStorageType Storage>
   174         EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
   198         Pose2D() : rot( RotationMath::Identity()), trans(Translation::Zero()) {}
   207                 rot( RotationMath::Rotation(angle)),
   208                 trans( (Translation() << x,y).finished() )
   222         template<
typename Rot, 
typename Trans>
   223         Pose2D(
const ecl::linear_algebra::MatrixBase<Rot>& R, 
const ecl::linear_algebra::MatrixBase<Trans>& T) :
   224                 rot( RotationMath::Rotation(R) ),
   237         template<
typename Trans>
   239                 rot( RotationMath::Rotation(angle) ),
   249         template <enum Pose2DStorageType Storage_>
   251                 rot(RotationMath::Rotation(pose.rotation())),
   252                 trans(pose.translation())
   265         template <enum Pose2DStorageType Storage_>
   267                 trans = pose.translation();
   268                 rot = RotationMath::Rotation(pose.rotation());
   284                 rot = RotationMath::Rotation(heading);
   294         void rotation(
const RotationMatrix &rotation_matrix) {
   295                 rot = RotationMath::Rotation(rotation_matrix);
   317         template <
typename Trans>
   318         void translation(
const ecl::linear_algebra::MatrixBase<Trans>& T) {
   326                 rot = RotationMath::Identity();
   342         void setPose(
const Float& x, 
const Float& y, 
const Angle<Float>& heading) { trans << x,y; rot = RotationMath::Rotation(heading); } 
   343         void x(
const Float& value) { trans[0] = value; }        
   344         void y(
const Float& value) { trans[1] = value; }        
   356         template <
typename Rot>
   357         void rotationMatrix(
const ecl::linear_algebra::MatrixBase<Rot>& rotation_matrix) {
   358                 rot = RotationMath::Rotation(rotation_matrix);
   366         const RotationType& 
rotation()
 const { 
return rot; } 
   372         Float 
x()
 const { 
return trans[0]; }            
   373         Float 
y()
 const { 
return trans[1]; }            
   375         RotationMatrix 
rotationMatrix()
 const { 
return RotationMatrixMath::Rotation(rot); } 
   389         inverse.rotation(RotationMath::Inverse(rot));
   390         inverse.translation(-1*(RotationMatrixMath::Rotation(inverse.rot)*trans));
   399         template <enum Pose2DStorageType Storage_>
   401                 return Pose2D<Float,Storage>(RotationMath::Product(rot,pose.rot),trans + rotationMatrix()*pose.trans);
   410         *
this = (*this)*pose;
   427         template <enum Pose2DStorageType Storage_>
   429                 return pose.inverse()*(*this);
   435         template <
typename OutputStream, 
typename Float_, enum Pose2DStorageType Storage_>
   436         friend OutputStream& operator<<(OutputStream &ostream , const Pose2D<Float_, Storage_> &pose);
   455 template <
typename OutputStream, 
typename Float_, enum Pose2DStorageType Storage_>
   456 OutputStream& operator<<(OutputStream &ostream , const Pose2D<Float_,Storage_> &pose) {
   461         ostream << format(pose.x()) << 
" ";
   462         ostream << format(pose.y()) << 
" ";
   463         ostream << format(pose.heading());
 geometry::Pose2DMath< Float, RotationAngleStorage > RotationAngleMath
Rotational math specific to rotational angles. 
Pose2D()
Default constructor. 
const Translation & translation() const 
Return a const handle to the rotational storage component. 
Forward declaration for a general purpose traits mechanims. 
ecl::linear_algebra::Matrix< Float, 2, 1 > Translation
The type used to represent translations. 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Float Scalar
Eigen style declaration of the element type. 
void rotationMatrix(const ecl::linear_algebra::MatrixBase< Rot > &rotation_matrix)
Set the rotational component. 
Pose2D(const Angle< Float > &angle, const ecl::linear_algebra::MatrixBase< Trans > &T)
Construct the pose using a rotational angle and a translation vector. 
void translation(const Float &x, const Float &y)
Set the translation vector from a pair of x,y values. 
Pose2D< Float, Storage > & operator=(const Pose2D< Float, Storage_ > &pose)
Assign from another Pose2D instance. 
Pose2D< Float, Storage > inverse() const 
Calculate the inverse pose. 
Math functions/selectors for the pose2D class with rotation angle storage. 
const RotationType & rotation() const 
Return a mutable handle to the translation vector. 
Default action for detection of a fundamental float type (false). 
Math functions/selectors for the pose2D class with rotation matrix storage. 
Parent template definition for Pose2D. 
Pose2D< Float, Storage > operator*(const Pose2D< Float, Storage_ > &pose) const 
Combine this pose with the incoming pose. 
Float Scalar
Element type. 
ecl::linear_algebra::Matrix< Float, 2, 2 > RotationType
Rotation storage type (matrix). 
void y(const Float &value)
Sets the y-coordinate. 
RotationMatrix rotationMatrix() const 
void rotation(const Angle< Float > &heading)
Set the rotational component with a heading angle. 
ecl::linear_algebra::Matrix< Float, 2, 2 > RotationMatrix
The type used to represent rotation matrices. 
Angle< Float > heading() const 
Get the heading. 
void heading(const Angle< Float > &value)
Sets the heading. 
geometry::Pose2DMath< Float, RotationMatrixStorage > RotationMatrixMath
Rotational math specific to rotational matrices. 
Translation & translation()
Return a mutable handle to the rotational storage component. 
void translation(const ecl::linear_algebra::MatrixBase< Trans > &T)
Set the translation vector. 
static Pose2D< Float, Storage > Identity()
Static function for returning the idenitity pose, eigen style. 
geometry::Pose2DMath< Float, Storage > RotationMath
Rotational math specific to this storage type. 
void setPose(const Float &x, const Float &y, const Angle< Float > &heading)
Sets the pose with a triplet. 
RotationType & rotation()
void x(const Float &value)
Sets the x-coordinate. 
ecl_traits< Pose2D< Float, Storage, typename enable_if< is_float< Float > >::type > >::RotationType RotationType
The type used for storage of the rotation/angle. 
Parent template definition for angles. 
Parent template for the pose2D math classes. 
void rotation(const RotationMatrix &rotation_matrix)
Set the rotational component with a rotation matrix. 
Angle< Float > RotationType
Rotation storage type (angle). 
Pose2D(const Float &x, const Float &y, const Angle< Float > &angle)
Construct the pose using scalars for position and rotation angle. 
Float x() const 
Return a const handle to the translation vector. 
Float Scalar
Element type. 
Enables the SFINAE concept. 
void setIdentity()
Set this pose to zero rotation and zero translation. 
Pose2D(const Pose2D< Float, Storage_ > &pose)
Copy constructor that works for copies from any pose type. 
Pose2D< Float > & operator*=(const Pose2D< Float > &pose)
Transform this pose by the specified input pose. 
Pose2D(const ecl::linear_algebra::MatrixBase< Rot > &R, const ecl::linear_algebra::MatrixBase< Trans > &T)
Construct the pose using a rotation matrix and a translation vector. 
Float y() const 
Get the y-coordinate. 
Pose2D< Float, Storage > relative(const Pose2D< Float, Storage_ > &pose) const 
Relative pose between this pose and another.