14 #ifndef ECL_GEOMETRY_LEGACY_POSE2D_HPP_
15 #define ECL_GEOMETRY_LEGACY_POSE2D_HPP_
54 template <
typename Float, enum Pose2DStorageType Storage,
typename Enable>
class LegacyPose2D;
67 template <
typename Float, enum Pose2DStorageType Storage,
typename Enable>
73 template <
typename Float,
typename Enable>
77 typedef ecl::linear_algebra::Matrix<Float,2,2>
RotationType;
83 template <
typename Float,
typename Enable>
102 template <
typename Float, enum Pose2DStorageType Storage>
class Pose2DMath {};
110 template <
typename Float>
113 typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrixType;
116 static RotationMatrixType Rotation(
const RotationMatrixType &rotation) {
return rotation; }
119 static RotationMatrixType Product(
const RotationMatrixType &rot1,
const RotationMatrixType &rot2) {
return rot1*rot2; }
120 static RotationMatrixType Product(
const RotationMatrixType &rotation,
const Angle<Float> &angle) {
return rotation*angle.rotationMatrix(); }
121 static RotationMatrixType Inverse(
const RotationMatrixType &rotation) {
return rotation.transpose(); }
131 template <
typename Float>
134 typedef ecl::linear_algebra::Matrix<Float,2,2> RotationMatrixType;
135 static Angle<Float> Identity() {
return Angle<Float>(0.0); }
141 static Angle<Float> Inverse(
const Angle<Float> &angle) {
return Angle<Float>(-1*angle); }
159 template <
class Float, enum Pose2DStorageType Storage = RotationMatrixStorage,
typename Enable =
void>
161 typedef Float Scalar;
182 template<
typename Float, enum Pose2DStorageType Storage>
188 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
193 typedef Float Scalar;
221 rot( RotationMath::Rotation(angle)),
236 template<
typename Rot,
typename Trans>
237 LegacyPose2D(
const ecl::linear_algebra::MatrixBase<Rot>& R,
const ecl::linear_algebra::MatrixBase<Trans>& T) :
238 rot( RotationMath::Rotation(R) ),
251 template<
typename Trans>
253 rot( RotationMath::Rotation(angle) ),
263 template <enum Pose2DStorageType Storage_>
265 rot(RotationMath::Rotation(pose.rotation())),
266 trans(pose.translation())
279 template <enum Pose2DStorageType Storage_>
281 trans = pose.translation();
282 rot = RotationMath::Rotation(pose.rotation());
298 rot = RotationMath::Rotation(heading);
308 void rotation(
const RotationMatrix &rotation_matrix) {
309 rot = RotationMath::Rotation(rotation_matrix);
319 void translation(
const Float &x,
const Float &y) {
331 template <
typename Trans>
332 void translation(
const ecl::linear_algebra::MatrixBase<Trans>& T) {
340 rot = RotationMath::Identity();
356 void setPose(
const Float& x,
const Float& y,
const Angle<Float>& heading) { trans << x,y; rot = RotationMath::Rotation(heading); }
357 void x(
const Float& value) { trans[0] = value; }
358 void y(
const Float& value) { trans[1] = value; }
359 void heading(
const Angle<Float>& value) { rot = RotationMath::Rotation(value); }
370 template <
typename Rot>
371 void rotationMatrix(
const ecl::linear_algebra::MatrixBase<Rot>& rotation_matrix) {
372 rot = RotationMath::Rotation(rotation_matrix);
378 RotationType& rotation() {
return rot; }
379 Translation& translation() {
return trans; }
386 Float x()
const {
return trans[0]; }
387 Float y()
const {
return trans[1]; }
388 Angle<Float> heading()
const {
return RotationMath::Heading(rot); }
389 RotationMatrix rotationMatrix()
const {
return RotationMatrixMath::Rotation(rot); }
401 LegacyPose2D<Float,Storage> inverse()
const {
402 LegacyPose2D<Float,Storage> inverse;
403 inverse.rotation(RotationMath::Inverse(rot));
404 inverse.translation(-1*(RotationMatrixMath::Rotation(inverse.rot)*trans));
413 template <enum Pose2DStorageType Storage_>
424 *
this = (*this)*pose;
441 template <enum Pose2DStorageType Storage_>
443 return pose.inverse()*(*this);
449 template <
typename OutputStream,
typename Float_, enum Pose2DStorageType Storage_>
474 template <
typename OutputStream,
typename Float_, enum Pose2DStorageType Storage_>
480 ostream << format(pose.x()) <<
" ";
481 ostream << format(pose.y()) <<
" ";
482 ostream << format(pose.heading());