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>
71 typedef ecl::linear_algebra::Matrix<Float,2,2> RotationType;
77 template <
typename Float,
typename Enable>
92 template <
typename Float, enum Pose2DStorageType Storage>
class Pose2DMath {};
100 template <
typename Float>
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>
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>
147 typedef Float Scalar;
168 template<
typename Float, enum Pose2DStorageType Storage>
174 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
179 typedef Float Scalar;
184 typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrix;
185 typedef ecl::linear_algebra::Matrix<Float,2,1> Translation;
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);
305 void translation(
const Float &x,
const Float &y) {
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; }
345 void heading(
const Angle<Float>& value) { rot = RotationMath::Rotation(value); }
356 template <
typename Rot>
357 void rotationMatrix(
const ecl::linear_algebra::MatrixBase<Rot>& rotation_matrix) {
358 rot = RotationMath::Rotation(rotation_matrix);
364 RotationType& rotation() {
return rot; }
365 Translation& translation() {
return trans; }
366 const RotationType& rotation()
const {
return rot; }
367 const Translation& translation()
const {
return trans; }
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); }
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());
Forward declaration for a general purpose traits mechanims.
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
void setIdentity(geometry_msgs::Transform &tx)
Math functions/selectors for the pose2D class with rotation angle storage.
Default action for detection of a fundamental float type (false).
Math functions/selectors for the pose2D class with rotation matrix storage.
TFSIMD_FORCE_INLINE const tfScalar & y() const
Parent template definition for Pose2D.
FloatingPoint< float > Float
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE Vector3 & operator*=(const tfScalar &s)
Parent template definition for angles.
Parent template for the pose2D math classes.
Enables the SFINAE concept.