pose2d.hpp
Go to the documentation of this file.
1 
10 /*****************************************************************************
11 ** Ifdefs
12 *****************************************************************************/
13 
14 #ifndef ECL_GEOMETRY_POSE2D_HPP_
15 #define ECL_GEOMETRY_POSE2D_HPP_
16 
17 /*****************************************************************************
18 ** Includes
19 *****************************************************************************/
20 
21 #include <ecl/linear_algebra.hpp>
22 
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>
30 #include "angle.hpp"
31 
32 /*****************************************************************************
33 ** Namespaces
34 *****************************************************************************/
35 
36 namespace ecl {
37 
38 /*****************************************************************************
39 ** Enums
40 *****************************************************************************/
47 };
48 
49 /*****************************************************************************
50 ** Forward declarations
51 *****************************************************************************/
52 
53 template <typename Float, enum Pose2DStorageType Storage, typename Enable> class Pose2D;
54 
55 /*****************************************************************************
56 ** Traits
57 *****************************************************************************/
61 template <typename Float, enum Pose2DStorageType Storage, typename Enable>
62 class ecl_traits< Pose2D<Float, Storage, Enable> > {};
63 
67 template <typename Float, typename Enable>
68 class ecl_traits< Pose2D<Float, RotationMatrixStorage, Enable> > {
69 public:
70  typedef Float Scalar;
71  typedef ecl::linear_algebra::Matrix<Float,2,2> RotationType;
72 };
73 
77 template <typename Float, typename Enable>
78 class ecl_traits< Pose2D<Float, RotationAngleStorage, Enable> > {
79 public:
80  typedef Float Scalar;
82 };
83 
84 namespace geometry {
85 
86 /*****************************************************************************
87 ** Operations
88 *****************************************************************************/
92 template <typename Float, enum Pose2DStorageType Storage> class Pose2DMath {};
100 template <typename Float>
101 class ECL_PUBLIC Pose2DMath<Float,RotationMatrixStorage> {
102 public:
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(); }
108  static Angle<Float> Heading(const RotationMatrixType &rotation) { return Angle<Float>(rotation); }
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(); }
112 };
113 
121 template <typename Float>
122 class ECL_PUBLIC Pose2DMath<Float,RotationAngleStorage> {
123 public:
124  typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrixType;
125  static Angle<Float> Identity() { return Angle<Float>(0.0); }
126  static Angle<Float> Rotation(const Angle<Float>& radians) { return Angle<Float>(radians); }
127  static Angle<Float> Rotation(const RotationMatrixType &rotation) { return Pose2DMath<Float,RotationMatrixStorage>::Heading(rotation); }
128  static Angle<Float> Heading(const Angle<Float> &angle) { return angle; }
129  static Angle<Float> Product(const Angle<Float> &angle1, const Angle<Float> &angle2) { return angle1+angle2; }
130  static Angle<Float> Product(const Angle<Float> &angle, RotationMatrixType &rotation) { return angle + Angle<Float>(rotation); }
131  static Angle<Float> Inverse(const Angle<Float> &angle) { return Angle<Float>(-1*angle); }
132 };
133 
134 } // namespace geometry
135 
136 
137 /*****************************************************************************
138 ** Pose2D
139 *****************************************************************************/
145 template <class Float, enum Pose2DStorageType Storage = RotationMatrixStorage, typename Enable = void>
146 class ECL_PUBLIC Pose2D {
147  typedef Float Scalar;
148 private:
149  Pose2D() {};
150 };
151 
168 template<typename Float, enum Pose2DStorageType Storage>
169 class ECL_PUBLIC Pose2D<Float, Storage, typename enable_if<is_float<Float> >::type> {
170 public:
171  /******************************************
172  ** Eigen Alignment
173  *******************************************/
174  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // http://eigen.tuxfamily.org/dox/StructHavingEigenMembers.html
175 
176  /******************************************
177  ** Typedef
178  *******************************************/
179  typedef Float Scalar;
184  typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrix;
185  typedef ecl::linear_algebra::Matrix<Float,2,1> Translation;
187  /******************************************
188  ** Constructors
189  *******************************************/
198  Pose2D() : rot( RotationMath::Identity()), trans(Translation::Zero()) {}
199 
206  Pose2D(const Float &x, const Float &y, const Angle<Float> &angle) :
207  rot( RotationMath::Rotation(angle)),
208  trans( (Translation() << x,y).finished() )
209  {}
210 
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) ),
225  trans(T)
226  {}
237  template<typename Trans>
238  Pose2D(const Angle<Float>& angle, const ecl::linear_algebra::MatrixBase<Trans>& T) :
239  rot( RotationMath::Rotation(angle) ),
240  trans(T)
241  {}
249  template <enum Pose2DStorageType Storage_>
251  rot(RotationMath::Rotation(pose.rotation())),
252  trans(pose.translation())
253  {}
254 
255  virtual ~Pose2D() {}
256 
257  /******************************************
258  ** Assignment
259  *******************************************/
265  template <enum Pose2DStorageType Storage_>
267  trans = pose.translation();
268  rot = RotationMath::Rotation(pose.rotation());
269  return *this;
270  }
271 
272  /******************************************
273  ** Eigen Style Setters
274  *******************************************/
283  void rotation(const Angle<Float> &heading) {
284  rot = RotationMath::Rotation(heading);
285  }
294  void rotation(const RotationMatrix &rotation_matrix) {
295  rot = RotationMath::Rotation(rotation_matrix);
296  }
305  void translation(const Float &x, const Float &y) {
306  this->trans << x, y;
307  }
317  template <typename Trans>
318  void translation(const ecl::linear_algebra::MatrixBase<Trans>& T) {
319  this->trans = T;
320  }
321 
325  void setIdentity() {
326  rot = RotationMath::Identity();
327  trans << 0.0, 0.0;
328  }
329 
336  return Pose2D<Float,Storage>();
337  }
338 
339  /******************************************
340  ** Convenience Setters
341  *******************************************/
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; }
345  void heading(const Angle<Float>& value) { rot = RotationMath::Rotation(value); }
346 
356  template <typename Rot>
357  void rotationMatrix(const ecl::linear_algebra::MatrixBase<Rot>& rotation_matrix) {
358  rot = RotationMath::Rotation(rotation_matrix);
359  }
360 
361  /******************************************
362  ** Eigen Style Accessors
363  *******************************************/
364  RotationType& rotation() { return rot; }
365  Translation& translation() { return trans; }
366  const RotationType& rotation() const { return rot; }
367  const Translation& translation() const { return trans; }
369  /******************************************
370  ** Convenience Accessors
371  *******************************************/
372  Float x() const { return trans[0]; }
373  Float y() const { return trans[1]; }
374  Angle<Float> heading() const { return RotationMath::Heading(rot); }
375  RotationMatrix rotationMatrix() const { return RotationMatrixMath::Rotation(rot); }
377  /******************************************
378  ** Operators
379  *******************************************/
388  Pose2D<Float,Storage> inverse;
389  inverse.rotation(RotationMath::Inverse(rot));
390  inverse.translation(-1*(RotationMatrixMath::Rotation(inverse.rot)*trans));
391  return inverse;
392  }
393 
399  template <enum Pose2DStorageType Storage_>
401  return Pose2D<Float,Storage>(RotationMath::Product(rot,pose.rot),trans + rotationMatrix()*pose.trans);
402  }
409  // This probably needs checking...could also be (marginally) sped up.
410  *this = (*this)*pose;
411  return (*this);
412  }
427  template <enum Pose2DStorageType Storage_>
429  return pose.inverse()*(*this);
430  }
431 
432  /*********************
433  ** Streaming
434  **********************/
435  template <typename OutputStream, typename Float_, enum Pose2DStorageType Storage_>
436  friend OutputStream& operator<<(OutputStream &ostream , const Pose2D<Float_, Storage_> &pose);
437 
438 private:
439  RotationType rot;
440  Translation trans;
441 };
442 
443 /*****************************************************************************
444 ** Insertion Operators
445 *****************************************************************************/
455 template <typename OutputStream, typename Float_, enum Pose2DStorageType Storage_>
456 OutputStream& operator<<(OutputStream &ostream , const Pose2D<Float_,Storage_> &pose) {
457  ecl::Format<Float_> format;
458  format.width(6);
459  format.precision(3);
460  ostream << "[ ";
461  ostream << format(pose.x()) << " ";
462  ostream << format(pose.y()) << " ";
463  ostream << format(pose.heading());
464  ostream << " ]";
465  ostream.flush();
466  return ostream;
467 }
468 
469 
470 } // namespace ecl
471 
472 // This is more convenient and less bughuntish than always assigning allocators with your vectors
473 // but currently fails on oneiric with gcc 4.6 (bugfixed in eigen, but not yet out in oneiric).
474 // EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(ecl::Pose2D<float,ecl::RotationAngleStorage>)
475 // EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(ecl::Pose2D<float,ecl::RotationMatrixStorage>)
476 // EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(ecl::Pose2D<double,ecl::RotationAngleStorage>)
477 // EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(ecl::Pose2D<double,ecl::RotationMatrixStorage>)
478 
479 #endif /* ECL_GEOMETRY_POSE2D_HPP_ */
geometry::Pose2DMath< Float, RotationAngleStorage > RotationAngleMath
Rotational math specific to rotational angles.
Definition: pose2d.hpp:182
const Translation & translation() const
Return a const handle to the rotational storage component.
Definition: pose2d.hpp:367
Forward declaration for a general purpose traits mechanims.
RotationMatrixStorage
ecl::linear_algebra::Matrix< Float, 2, 1 > Translation
The type used to represent translations.
Definition: pose2d.hpp:185
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Float Scalar
Eigen style declaration of the element type.
Definition: pose2d.hpp:179
Float Scalar
Definition: pose2d.hpp:147
void rotationMatrix(const ecl::linear_algebra::MatrixBase< Rot > &rotation_matrix)
Set the rotational component.
Definition: pose2d.hpp:357
RotationAngleStorage
Pose2D(const Angle< Float > &angle, const ecl::linear_algebra::MatrixBase< Trans > &T)
Construct the pose using a rotational angle and a translation vector.
Definition: pose2d.hpp:238
void translation(const Float &x, const Float &y)
Set the translation vector from a pair of x,y values.
Definition: pose2d.hpp:305
Pose2D< Float, Storage > & operator=(const Pose2D< Float, Storage_ > &pose)
Assign from another Pose2D instance.
Definition: pose2d.hpp:266
Pose2D< Float, Storage > inverse() const
Calculate the inverse pose.
Definition: pose2d.hpp:387
Math functions/selectors for the pose2D class with rotation angle storage.
Definition: pose2d.hpp:122
const RotationType & rotation() const
Return a mutable handle to the translation vector.
Definition: pose2d.hpp:366
Default action for detection of a fundamental float type (false).
Pose2DStorageType
Math functions/selectors for the pose2D class with rotation matrix storage.
Definition: pose2d.hpp:101
Parent template definition for Pose2D.
Definition: pose2d.hpp:53
Pose2D< Float, Storage > operator*(const Pose2D< Float, Storage_ > &pose) const
Combine this pose with the incoming pose.
Definition: pose2d.hpp:400
Primary template for all formatter classes.
Definition: common.hpp:99
#define ECL_PUBLIC
ecl::linear_algebra::Matrix< Float, 2, 2 > RotationType
Rotation storage type (matrix).
Definition: pose2d.hpp:71
void y(const Float &value)
Sets the y-coordinate.
Definition: pose2d.hpp:344
void rotation(const Angle< Float > &heading)
Set the rotational component with a heading angle.
Definition: pose2d.hpp:283
ecl::linear_algebra::Matrix< Float, 2, 2 > RotationMatrix
The type used to represent rotation matrices.
Definition: pose2d.hpp:184
Angle< Float > heading() const
Get the heading.
Definition: pose2d.hpp:374
void heading(const Angle< Float > &value)
Sets the heading.
Definition: pose2d.hpp:345
geometry::Pose2DMath< Float, RotationMatrixStorage > RotationMatrixMath
Rotational math specific to rotational matrices.
Definition: pose2d.hpp:181
Translation & translation()
Return a mutable handle to the rotational storage component.
Definition: pose2d.hpp:365
void translation(const ecl::linear_algebra::MatrixBase< Trans > &T)
Set the translation vector.
Definition: pose2d.hpp:318
static Pose2D< Float, Storage > Identity()
Static function for returning the idenitity pose, eigen style.
Definition: pose2d.hpp:335
geometry::Pose2DMath< Float, Storage > RotationMath
Rotational math specific to this storage type.
Definition: pose2d.hpp:180
void setPose(const Float &x, const Float &y, const Angle< Float > &heading)
Sets the pose with a triplet.
Definition: pose2d.hpp:342
void x(const Float &value)
Sets the x-coordinate.
Definition: pose2d.hpp:343
ecl_traits< Pose2D< Float, Storage, typename enable_if< is_float< Float > >::type > >::RotationType RotationType
The type used for storage of the rotation/angle.
Definition: pose2d.hpp:183
Parent template definition for angles.
Definition: angle.hpp:113
Parent template for the pose2D math classes.
Definition: pose2d.hpp:92
void rotation(const RotationMatrix &rotation_matrix)
Set the rotational component with a rotation matrix.
Definition: pose2d.hpp:294
Angle< Float > RotationType
Rotation storage type (angle).
Definition: pose2d.hpp:81
Pose2D(const Float &x, const Float &y, const Angle< Float > &angle)
Construct the pose using scalars for position and rotation angle.
Definition: pose2d.hpp:206
Float x() const
Return a const handle to the translation vector.
Definition: pose2d.hpp:372
Enables the SFINAE concept.
Definition: enable_if.hpp:67
void setIdentity()
Set this pose to zero rotation and zero translation.
Definition: pose2d.hpp:325
Pose2D(const Pose2D< Float, Storage_ > &pose)
Copy constructor that works for copies from any pose type.
Definition: pose2d.hpp:250
Pose2D< Float > & operator*=(const Pose2D< Float > &pose)
Transform this pose by the specified input pose.
Definition: pose2d.hpp:408
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.
Definition: pose2d.hpp:223
Pose2D< Float, Storage > relative(const Pose2D< Float, Storage_ > &pose) const
Relative pose between this pose and another.
Definition: pose2d.hpp:428


xbot_driver
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:27:37