Go to the documentation of this file.00001
00010
00011
00012
00013
00014 #ifndef ECL_GEOMETRY_LEGACY_POSE3D_HPP_
00015 #define ECL_GEOMETRY_LEGACY_POSE3D_HPP_
00016
00017
00018
00019
00020
00021 #include <ecl/linear_algebra.hpp>
00022
00023 #include <ecl/config/macros.hpp>
00024
00025 #include "legacy_pose2d.hpp"
00026
00027
00028
00029
00030
00031 namespace ecl {
00032
00033
00034
00035
00036
00042 template <class Float, typename Enable = void>
00043 class ECL_LOCAL LegacyPose3D {
00044 private:
00045 LegacyPose3D() {};
00046 };
00047
00059 template<typename Float>
00060 class ECL_PUBLIC LegacyPose3D<Float, typename enable_if<is_float<Float> >::type> {
00061 public:
00062
00063
00064
00065 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00066
00067
00068
00069
00070 typedef Float Scalar;
00071 typedef ecl::linear_algebra::Matrix<Float,3,3> RotationMatrix;
00072 typedef ecl::linear_algebra::Matrix<Float,3,1> Translation;
00074
00075
00076
00080 LegacyPose3D() : rot(RotationMatrix::Identity()), trans(Translation::Zero()) {}
00081
00093 template<typename Rot, typename Trans>
00094
00095 LegacyPose3D(const ecl::linear_algebra::EigenBase<Rot>& rotation, const ecl::linear_algebra::EigenBase<Trans>& translation) :
00096 rot(rotation),
00097 trans(translation)
00098 {}
00099
00106 template <enum Pose2DStorageType Storage_>
00107 LegacyPose3D(const LegacyPose2D<Float,Storage_>& pose) :
00108 rot(RotationMatrix::Identity()),
00109 trans(Translation::Zero())
00110 {
00111 rot.template block<2,2>(0,0) = pose.rotationMatrix();
00112 trans.template segment<2>(0) = pose.translation();
00113 }
00114
00122 template<typename Trans>
00123 LegacyPose3D(const ecl::linear_algebra::AngleAxis<Float>& angle_axis, const ecl::linear_algebra::MatrixBase<Trans>& translation) :
00124 rot(RotationMatrix::Identity()),
00125 trans(Translation::Zero())
00126 {
00127
00128 }
00136 template<typename Trans>
00137 LegacyPose3D(const ecl::linear_algebra::Quaternion<Float>& quaternion, const ecl::linear_algebra::MatrixBase<Trans>& translation) :
00138 rot(quaternion.toRotationMatrix()),
00139 trans(translation)
00140 {}
00141
00146 LegacyPose3D(const LegacyPose3D<Float>& pose) :
00147 rot(pose.rotation()),
00148 trans(pose.translation())
00149 {}
00150
00151 virtual ~LegacyPose3D() {}
00152
00153
00154
00155
00161 template <enum Pose2DStorageType Storage_>
00162 LegacyPose3D<Float>& operator=(const LegacyPose2D<Float,Storage_>& pose) {
00163 rot.template block<2,2>(0,0) = pose.rotationMatrix();
00164 (rot.template block<2,1>(0,2)) << 0.0, 0.0;
00165 (rot.template block<1,3>(2,0)) << 0.0, 0.0, 1.0;
00166 trans.template segment<2>(0) = pose.translation();
00167 trans[2] = 0.0;
00168 return *this;
00169 }
00170
00176 LegacyPose3D<Float>& operator=(const LegacyPose3D<Float>& pose) {
00177 rot = pose.rotation();
00178 trans = pose.translation();
00179 return *this;
00180 }
00181
00182
00183
00191 void rotation(const RotationMatrix &rotation) {
00192 rot = rotation;
00193 }
00203 template <typename Trans>
00204 void translation(const ecl::linear_algebra::MatrixBase<Trans>& translation) {
00205 this->trans = translation;
00206 }
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217 RotationMatrix& rotation() { return rot; }
00218 Translation& translation() { return trans; }
00219 const RotationMatrix& rotation() const { return rot; }
00220 const Translation& translation() const { return trans; }
00222
00223
00224
00225
00226
00227
00228 RotationMatrix rotationMatrix() const { return rot; }
00230
00231
00232
00240 LegacyPose3D<Float> inverse() const {
00241 LegacyPose3D<Float> inverse;
00242 inverse.rotation(rot.transpose());
00243 inverse.translation(-1*(inverse.rot*trans));
00244 return inverse;
00245 }
00251 template <typename Float_>
00252 LegacyPose3D<Float> operator*(const LegacyPose3D<Float_> &pose) const {
00253 return LegacyPose3D<Float>(rotation()*pose.rotation(),translation() + rotation()*pose.translation());
00254 }
00255
00256
00257
00258
00264 template <typename Float_>
00265 LegacyPose3D<Float>& operator*=(const LegacyPose3D<Float_> &pose) {
00266
00267 *this = (*this)*pose;
00268 return (*this);
00269 }
00278 template <typename Float_>
00279 LegacyPose3D<Float> relative(const LegacyPose3D<Float_> &pose) const {
00280 return pose.inverse()*(*this);
00281 }
00282
00283
00284
00285
00286
00287
00288 template <typename OutputStream, typename Float_>
00289 friend OutputStream& operator<<(OutputStream &ostream , const LegacyPose3D<Float_> &pose);
00290
00291 private:
00292 RotationMatrix rot;
00293 Translation trans;
00294 };
00295
00296
00297
00298
00308 template <typename OutputStream, typename Float_>
00309 OutputStream& operator<<(OutputStream &ostream , const LegacyPose3D<Float_> &pose) {
00310 ecl::Format<Float_> format;
00311 format.width(6);
00312 format.precision(3);
00313 for ( unsigned int i = 0; i < 3; ++i ) {
00314 ostream << "[ ";
00315 for ( unsigned int j = 0; j < 3; ++j ) {
00316 ostream << format(pose.rot(i,j)) << " ";
00317 }
00318 ostream << "] [ ";
00319 ostream << format(pose.trans(i)) << " ]\n";
00320 }
00321 ostream.flush();
00322 return ostream;
00323 }
00324
00325 }
00326
00327
00328
00329
00330
00331
00332 #endif