00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 #ifndef EIGEN_TRANSFORM_H
00013 #define EIGEN_TRANSFORM_H
00014
00015 namespace Eigen {
00016
00017 namespace internal {
00018
00019 template<typename Transform>
00020 struct transform_traits
00021 {
00022 enum
00023 {
00024 Dim = Transform::Dim,
00025 HDim = Transform::HDim,
00026 Mode = Transform::Mode,
00027 IsProjective = (int(Mode)==int(Projective))
00028 };
00029 };
00030
00031 template< typename TransformType,
00032 typename MatrixType,
00033 int Case = transform_traits<TransformType>::IsProjective ? 0
00034 : int(MatrixType::RowsAtCompileTime) == int(transform_traits<TransformType>::HDim) ? 1
00035 : 2>
00036 struct transform_right_product_impl;
00037
00038 template< typename Other,
00039 int Mode,
00040 int Options,
00041 int Dim,
00042 int HDim,
00043 int OtherRows=Other::RowsAtCompileTime,
00044 int OtherCols=Other::ColsAtCompileTime>
00045 struct transform_left_product_impl;
00046
00047 template< typename Lhs,
00048 typename Rhs,
00049 bool AnyProjective =
00050 transform_traits<Lhs>::IsProjective ||
00051 transform_traits<Rhs>::IsProjective>
00052 struct transform_transform_product_impl;
00053
00054 template< typename Other,
00055 int Mode,
00056 int Options,
00057 int Dim,
00058 int HDim,
00059 int OtherRows=Other::RowsAtCompileTime,
00060 int OtherCols=Other::ColsAtCompileTime>
00061 struct transform_construct_from_matrix;
00062
00063 template<typename TransformType> struct transform_take_affine_part;
00064
00065 }
00066
00175 template<typename _Scalar, int _Dim, int _Mode, int _Options>
00176 class Transform
00177 {
00178 public:
00179 EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_Dim==Dynamic ? Dynamic : (_Dim+1)*(_Dim+1))
00180 enum {
00181 Mode = _Mode,
00182 Options = _Options,
00183 Dim = _Dim,
00184 HDim = _Dim+1,
00185 Rows = int(Mode)==(AffineCompact) ? Dim : HDim
00186 };
00188 typedef _Scalar Scalar;
00189 typedef DenseIndex Index;
00191 typedef typename internal::make_proper_matrix_type<Scalar,Rows,HDim,Options>::type MatrixType;
00193 typedef const MatrixType ConstMatrixType;
00195 typedef Matrix<Scalar,Dim,Dim,Options> LinearMatrixType;
00197 typedef Block<MatrixType,Dim,Dim,int(Mode)==(AffineCompact)> LinearPart;
00199 typedef const Block<ConstMatrixType,Dim,Dim,int(Mode)==(AffineCompact)> ConstLinearPart;
00201 typedef typename internal::conditional<int(Mode)==int(AffineCompact),
00202 MatrixType&,
00203 Block<MatrixType,Dim,HDim> >::type AffinePart;
00205 typedef typename internal::conditional<int(Mode)==int(AffineCompact),
00206 const MatrixType&,
00207 const Block<const MatrixType,Dim,HDim> >::type ConstAffinePart;
00209 typedef Matrix<Scalar,Dim,1> VectorType;
00211 typedef Block<MatrixType,Dim,1,int(Mode)==(AffineCompact)> TranslationPart;
00213 typedef const Block<ConstMatrixType,Dim,1,int(Mode)==(AffineCompact)> ConstTranslationPart;
00215 typedef Translation<Scalar,Dim> TranslationType;
00216
00217
00218 enum { TransformTimeDiagonalMode = ((Mode==int(Isometry))?Affine:int(Mode)) };
00220 typedef Transform<Scalar,Dim,TransformTimeDiagonalMode> TransformTimeDiagonalReturnType;
00221
00222 protected:
00223
00224 MatrixType m_matrix;
00225
00226 public:
00227
00230 inline Transform()
00231 {
00232 check_template_params();
00233 if (int(Mode)==Affine)
00234 makeAffine();
00235 }
00236
00237 inline Transform(const Transform& other)
00238 {
00239 check_template_params();
00240 m_matrix = other.m_matrix;
00241 }
00242
00243 inline explicit Transform(const TranslationType& t)
00244 {
00245 check_template_params();
00246 *this = t;
00247 }
00248 inline explicit Transform(const UniformScaling<Scalar>& s)
00249 {
00250 check_template_params();
00251 *this = s;
00252 }
00253 template<typename Derived>
00254 inline explicit Transform(const RotationBase<Derived, Dim>& r)
00255 {
00256 check_template_params();
00257 *this = r;
00258 }
00259
00260 inline Transform& operator=(const Transform& other)
00261 { m_matrix = other.m_matrix; return *this; }
00262
00263 typedef internal::transform_take_affine_part<Transform> take_affine_part;
00264
00266 template<typename OtherDerived>
00267 inline explicit Transform(const EigenBase<OtherDerived>& other)
00268 {
00269 EIGEN_STATIC_ASSERT((internal::is_same<Scalar,typename OtherDerived::Scalar>::value),
00270 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY);
00271
00272 check_template_params();
00273 internal::transform_construct_from_matrix<OtherDerived,Mode,Options,Dim,HDim>::run(this, other.derived());
00274 }
00275
00277 template<typename OtherDerived>
00278 inline Transform& operator=(const EigenBase<OtherDerived>& other)
00279 {
00280 EIGEN_STATIC_ASSERT((internal::is_same<Scalar,typename OtherDerived::Scalar>::value),
00281 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY);
00282
00283 internal::transform_construct_from_matrix<OtherDerived,Mode,Options,Dim,HDim>::run(this, other.derived());
00284 return *this;
00285 }
00286
00287 template<int OtherOptions>
00288 inline Transform(const Transform<Scalar,Dim,Mode,OtherOptions>& other)
00289 {
00290 check_template_params();
00291
00292 m_matrix = other.matrix();
00293 }
00294
00295 template<int OtherMode,int OtherOptions>
00296 inline Transform(const Transform<Scalar,Dim,OtherMode,OtherOptions>& other)
00297 {
00298 check_template_params();
00299
00300
00301 EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Projective), Mode==int(Projective)),
00302 YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION)
00303
00304
00305
00306 EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Affine)||OtherMode==int(AffineCompact), Mode!=int(Isometry)),
00307 YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION)
00308
00309 enum { ModeIsAffineCompact = Mode == int(AffineCompact),
00310 OtherModeIsAffineCompact = OtherMode == int(AffineCompact)
00311 };
00312
00313 if(ModeIsAffineCompact == OtherModeIsAffineCompact)
00314 {
00315
00316
00317
00318 m_matrix.template block<Dim,Dim+1>(0,0) = other.matrix().template block<Dim,Dim+1>(0,0);
00319 makeAffine();
00320 }
00321 else if(OtherModeIsAffineCompact)
00322 {
00323 typedef typename Transform<Scalar,Dim,OtherMode,OtherOptions>::MatrixType OtherMatrixType;
00324 internal::transform_construct_from_matrix<OtherMatrixType,Mode,Options,Dim,HDim>::run(this, other.matrix());
00325 }
00326 else
00327 {
00328
00329
00330
00331 linear() = other.linear();
00332 translation() = other.translation();
00333 }
00334 }
00335
00336 template<typename OtherDerived>
00337 Transform(const ReturnByValue<OtherDerived>& other)
00338 {
00339 check_template_params();
00340 other.evalTo(*this);
00341 }
00342
00343 template<typename OtherDerived>
00344 Transform& operator=(const ReturnByValue<OtherDerived>& other)
00345 {
00346 other.evalTo(*this);
00347 return *this;
00348 }
00349
00350 #ifdef EIGEN_QT_SUPPORT
00351 inline Transform(const QMatrix& other);
00352 inline Transform& operator=(const QMatrix& other);
00353 inline QMatrix toQMatrix(void) const;
00354 inline Transform(const QTransform& other);
00355 inline Transform& operator=(const QTransform& other);
00356 inline QTransform toQTransform(void) const;
00357 #endif
00358
00361 inline Scalar operator() (Index row, Index col) const { return m_matrix(row,col); }
00364 inline Scalar& operator() (Index row, Index col) { return m_matrix(row,col); }
00365
00367 inline const MatrixType& matrix() const { return m_matrix; }
00369 inline MatrixType& matrix() { return m_matrix; }
00370
00372 inline ConstLinearPart linear() const { return ConstLinearPart(m_matrix,0,0); }
00374 inline LinearPart linear() { return LinearPart(m_matrix,0,0); }
00375
00377 inline ConstAffinePart affine() const { return take_affine_part::run(m_matrix); }
00379 inline AffinePart affine() { return take_affine_part::run(m_matrix); }
00380
00382 inline ConstTranslationPart translation() const { return ConstTranslationPart(m_matrix,0,Dim); }
00384 inline TranslationPart translation() { return TranslationPart(m_matrix,0,Dim); }
00385
00397
00398 template<typename OtherDerived>
00399 EIGEN_STRONG_INLINE const typename internal::transform_right_product_impl<Transform, OtherDerived>::ResultType
00400 operator * (const EigenBase<OtherDerived> &other) const
00401 { return internal::transform_right_product_impl<Transform, OtherDerived>::run(*this,other.derived()); }
00402
00410 template<typename OtherDerived> friend
00411 inline const typename internal::transform_left_product_impl<OtherDerived,Mode,Options,_Dim,_Dim+1>::ResultType
00412 operator * (const EigenBase<OtherDerived> &a, const Transform &b)
00413 { return internal::transform_left_product_impl<OtherDerived,Mode,Options,Dim,HDim>::run(a.derived(),b); }
00414
00421 template<typename DiagonalDerived>
00422 inline const TransformTimeDiagonalReturnType
00423 operator * (const DiagonalBase<DiagonalDerived> &b) const
00424 {
00425 TransformTimeDiagonalReturnType res(*this);
00426 res.linear() *= b;
00427 return res;
00428 }
00429
00436 template<typename DiagonalDerived>
00437 friend inline TransformTimeDiagonalReturnType
00438 operator * (const DiagonalBase<DiagonalDerived> &a, const Transform &b)
00439 {
00440 TransformTimeDiagonalReturnType res;
00441 res.linear().noalias() = a*b.linear();
00442 res.translation().noalias() = a*b.translation();
00443 if (Mode!=int(AffineCompact))
00444 res.matrix().row(Dim) = b.matrix().row(Dim);
00445 return res;
00446 }
00447
00448 template<typename OtherDerived>
00449 inline Transform& operator*=(const EigenBase<OtherDerived>& other) { return *this = *this * other; }
00450
00452 inline const Transform operator * (const Transform& other) const
00453 {
00454 return internal::transform_transform_product_impl<Transform,Transform>::run(*this,other);
00455 }
00456
00457 #ifdef __INTEL_COMPILER
00458 private:
00459
00460
00461
00462
00463
00464
00465
00466 template<int OtherMode,int OtherOptions> struct icc_11_workaround
00467 {
00468 typedef internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> > ProductType;
00469 typedef typename ProductType::ResultType ResultType;
00470 };
00471
00472 public:
00474 template<int OtherMode,int OtherOptions>
00475 inline typename icc_11_workaround<OtherMode,OtherOptions>::ResultType
00476 operator * (const Transform<Scalar,Dim,OtherMode,OtherOptions>& other) const
00477 {
00478 typedef typename icc_11_workaround<OtherMode,OtherOptions>::ProductType ProductType;
00479 return ProductType::run(*this,other);
00480 }
00481 #else
00482
00483 template<int OtherMode,int OtherOptions>
00484 inline typename internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> >::ResultType
00485 operator * (const Transform<Scalar,Dim,OtherMode,OtherOptions>& other) const
00486 {
00487 return internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> >::run(*this,other);
00488 }
00489 #endif
00490
00492 void setIdentity() { m_matrix.setIdentity(); }
00493
00498 static const Transform Identity()
00499 {
00500 return Transform(MatrixType::Identity());
00501 }
00502
00503 template<typename OtherDerived>
00504 inline Transform& scale(const MatrixBase<OtherDerived> &other);
00505
00506 template<typename OtherDerived>
00507 inline Transform& prescale(const MatrixBase<OtherDerived> &other);
00508
00509 inline Transform& scale(Scalar s);
00510 inline Transform& prescale(Scalar s);
00511
00512 template<typename OtherDerived>
00513 inline Transform& translate(const MatrixBase<OtherDerived> &other);
00514
00515 template<typename OtherDerived>
00516 inline Transform& pretranslate(const MatrixBase<OtherDerived> &other);
00517
00518 template<typename RotationType>
00519 inline Transform& rotate(const RotationType& rotation);
00520
00521 template<typename RotationType>
00522 inline Transform& prerotate(const RotationType& rotation);
00523
00524 Transform& shear(Scalar sx, Scalar sy);
00525 Transform& preshear(Scalar sx, Scalar sy);
00526
00527 inline Transform& operator=(const TranslationType& t);
00528 inline Transform& operator*=(const TranslationType& t) { return translate(t.vector()); }
00529 inline Transform operator*(const TranslationType& t) const;
00530
00531 inline Transform& operator=(const UniformScaling<Scalar>& t);
00532 inline Transform& operator*=(const UniformScaling<Scalar>& s) { return scale(s.factor()); }
00533 inline Transform<Scalar,Dim,(int(Mode)==int(Isometry)?Affine:Isometry)> operator*(const UniformScaling<Scalar>& s) const
00534 {
00535 Transform<Scalar,Dim,(int(Mode)==int(Isometry)?Affine:Isometry),Options> res = *this;
00536 res.scale(s.factor());
00537 return res;
00538 }
00539
00540 inline Transform& operator*=(const DiagonalMatrix<Scalar,Dim>& s) { linear() *= s; return *this; }
00541
00542 template<typename Derived>
00543 inline Transform& operator=(const RotationBase<Derived,Dim>& r);
00544 template<typename Derived>
00545 inline Transform& operator*=(const RotationBase<Derived,Dim>& r) { return rotate(r.toRotationMatrix()); }
00546 template<typename Derived>
00547 inline Transform operator*(const RotationBase<Derived,Dim>& r) const;
00548
00549 const LinearMatrixType rotation() const;
00550 template<typename RotationMatrixType, typename ScalingMatrixType>
00551 void computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const;
00552 template<typename ScalingMatrixType, typename RotationMatrixType>
00553 void computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const;
00554
00555 template<typename PositionDerived, typename OrientationType, typename ScaleDerived>
00556 Transform& fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,
00557 const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale);
00558
00559 inline Transform inverse(TransformTraits traits = (TransformTraits)Mode) const;
00560
00562 const Scalar* data() const { return m_matrix.data(); }
00564 Scalar* data() { return m_matrix.data(); }
00565
00571 template<typename NewScalarType>
00572 inline typename internal::cast_return_type<Transform,Transform<NewScalarType,Dim,Mode,Options> >::type cast() const
00573 { return typename internal::cast_return_type<Transform,Transform<NewScalarType,Dim,Mode,Options> >::type(*this); }
00574
00576 template<typename OtherScalarType>
00577 inline explicit Transform(const Transform<OtherScalarType,Dim,Mode,Options>& other)
00578 {
00579 check_template_params();
00580 m_matrix = other.matrix().template cast<Scalar>();
00581 }
00582
00587 bool isApprox(const Transform& other, typename NumTraits<Scalar>::Real prec = NumTraits<Scalar>::dummy_precision()) const
00588 { return m_matrix.isApprox(other.m_matrix, prec); }
00589
00592 void makeAffine()
00593 {
00594 if(int(Mode)!=int(AffineCompact))
00595 {
00596 matrix().template block<1,Dim>(Dim,0).setZero();
00597 matrix().coeffRef(Dim,Dim) = Scalar(1);
00598 }
00599 }
00600
00605 inline Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,Dim> linearExt()
00606 { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,Dim>(0,0); }
00611 inline const Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,Dim> linearExt() const
00612 { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,Dim>(0,0); }
00613
00618 inline Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,1> translationExt()
00619 { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,1>(0,Dim); }
00624 inline const Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,1> translationExt() const
00625 { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,1>(0,Dim); }
00626
00627
00628 #ifdef EIGEN_TRANSFORM_PLUGIN
00629 #include EIGEN_TRANSFORM_PLUGIN
00630 #endif
00631
00632 protected:
00633 #ifndef EIGEN_PARSED_BY_DOXYGEN
00634 static EIGEN_STRONG_INLINE void check_template_params()
00635 {
00636 EIGEN_STATIC_ASSERT((Options & (DontAlign|RowMajor)) == Options, INVALID_MATRIX_TEMPLATE_PARAMETERS)
00637 }
00638 #endif
00639
00640 };
00641
00643 typedef Transform<float,2,Isometry> Isometry2f;
00645 typedef Transform<float,3,Isometry> Isometry3f;
00647 typedef Transform<double,2,Isometry> Isometry2d;
00649 typedef Transform<double,3,Isometry> Isometry3d;
00650
00652 typedef Transform<float,2,Affine> Affine2f;
00654 typedef Transform<float,3,Affine> Affine3f;
00656 typedef Transform<double,2,Affine> Affine2d;
00658 typedef Transform<double,3,Affine> Affine3d;
00659
00661 typedef Transform<float,2,AffineCompact> AffineCompact2f;
00663 typedef Transform<float,3,AffineCompact> AffineCompact3f;
00665 typedef Transform<double,2,AffineCompact> AffineCompact2d;
00667 typedef Transform<double,3,AffineCompact> AffineCompact3d;
00668
00670 typedef Transform<float,2,Projective> Projective2f;
00672 typedef Transform<float,3,Projective> Projective3f;
00674 typedef Transform<double,2,Projective> Projective2d;
00676 typedef Transform<double,3,Projective> Projective3d;
00677
00678
00679
00680
00681
00682 #ifdef EIGEN_QT_SUPPORT
00683
00687 template<typename Scalar, int Dim, int Mode,int Options>
00688 Transform<Scalar,Dim,Mode,Options>::Transform(const QMatrix& other)
00689 {
00690 check_template_params();
00691 *this = other;
00692 }
00693
00698 template<typename Scalar, int Dim, int Mode,int Options>
00699 Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const QMatrix& other)
00700 {
00701 EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)
00702 m_matrix << other.m11(), other.m21(), other.dx(),
00703 other.m12(), other.m22(), other.dy(),
00704 0, 0, 1;
00705 return *this;
00706 }
00707
00714 template<typename Scalar, int Dim, int Mode, int Options>
00715 QMatrix Transform<Scalar,Dim,Mode,Options>::toQMatrix(void) const
00716 {
00717 check_template_params();
00718 EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)
00719 return QMatrix(m_matrix.coeff(0,0), m_matrix.coeff(1,0),
00720 m_matrix.coeff(0,1), m_matrix.coeff(1,1),
00721 m_matrix.coeff(0,2), m_matrix.coeff(1,2));
00722 }
00723
00728 template<typename Scalar, int Dim, int Mode,int Options>
00729 Transform<Scalar,Dim,Mode,Options>::Transform(const QTransform& other)
00730 {
00731 check_template_params();
00732 *this = other;
00733 }
00734
00739 template<typename Scalar, int Dim, int Mode, int Options>
00740 Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const QTransform& other)
00741 {
00742 check_template_params();
00743 EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)
00744 if (Mode == int(AffineCompact))
00745 m_matrix << other.m11(), other.m21(), other.dx(),
00746 other.m12(), other.m22(), other.dy();
00747 else
00748 m_matrix << other.m11(), other.m21(), other.dx(),
00749 other.m12(), other.m22(), other.dy(),
00750 other.m13(), other.m23(), other.m33();
00751 return *this;
00752 }
00753
00758 template<typename Scalar, int Dim, int Mode, int Options>
00759 QTransform Transform<Scalar,Dim,Mode,Options>::toQTransform(void) const
00760 {
00761 EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)
00762 if (Mode == int(AffineCompact))
00763 return QTransform(m_matrix.coeff(0,0), m_matrix.coeff(1,0),
00764 m_matrix.coeff(0,1), m_matrix.coeff(1,1),
00765 m_matrix.coeff(0,2), m_matrix.coeff(1,2));
00766 else
00767 return QTransform(m_matrix.coeff(0,0), m_matrix.coeff(1,0), m_matrix.coeff(2,0),
00768 m_matrix.coeff(0,1), m_matrix.coeff(1,1), m_matrix.coeff(2,1),
00769 m_matrix.coeff(0,2), m_matrix.coeff(1,2), m_matrix.coeff(2,2));
00770 }
00771 #endif
00772
00773
00774
00775
00776
00781 template<typename Scalar, int Dim, int Mode, int Options>
00782 template<typename OtherDerived>
00783 Transform<Scalar,Dim,Mode,Options>&
00784 Transform<Scalar,Dim,Mode,Options>::scale(const MatrixBase<OtherDerived> &other)
00785 {
00786 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))
00787 EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)
00788 linearExt().noalias() = (linearExt() * other.asDiagonal());
00789 return *this;
00790 }
00791
00796 template<typename Scalar, int Dim, int Mode, int Options>
00797 inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::scale(Scalar s)
00798 {
00799 EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)
00800 linearExt() *= s;
00801 return *this;
00802 }
00803
00808 template<typename Scalar, int Dim, int Mode, int Options>
00809 template<typename OtherDerived>
00810 Transform<Scalar,Dim,Mode,Options>&
00811 Transform<Scalar,Dim,Mode,Options>::prescale(const MatrixBase<OtherDerived> &other)
00812 {
00813 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))
00814 EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)
00815 m_matrix.template block<Dim,HDim>(0,0).noalias() = (other.asDiagonal() * m_matrix.template block<Dim,HDim>(0,0));
00816 return *this;
00817 }
00818
00823 template<typename Scalar, int Dim, int Mode, int Options>
00824 inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::prescale(Scalar s)
00825 {
00826 EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)
00827 m_matrix.template topRows<Dim>() *= s;
00828 return *this;
00829 }
00830
00835 template<typename Scalar, int Dim, int Mode, int Options>
00836 template<typename OtherDerived>
00837 Transform<Scalar,Dim,Mode,Options>&
00838 Transform<Scalar,Dim,Mode,Options>::translate(const MatrixBase<OtherDerived> &other)
00839 {
00840 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))
00841 translationExt() += linearExt() * other;
00842 return *this;
00843 }
00844
00849 template<typename Scalar, int Dim, int Mode, int Options>
00850 template<typename OtherDerived>
00851 Transform<Scalar,Dim,Mode,Options>&
00852 Transform<Scalar,Dim,Mode,Options>::pretranslate(const MatrixBase<OtherDerived> &other)
00853 {
00854 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))
00855 if(int(Mode)==int(Projective))
00856 affine() += other * m_matrix.row(Dim);
00857 else
00858 translation() += other;
00859 return *this;
00860 }
00861
00879 template<typename Scalar, int Dim, int Mode, int Options>
00880 template<typename RotationType>
00881 Transform<Scalar,Dim,Mode,Options>&
00882 Transform<Scalar,Dim,Mode,Options>::rotate(const RotationType& rotation)
00883 {
00884 linearExt() *= internal::toRotationMatrix<Scalar,Dim>(rotation);
00885 return *this;
00886 }
00887
00895 template<typename Scalar, int Dim, int Mode, int Options>
00896 template<typename RotationType>
00897 Transform<Scalar,Dim,Mode,Options>&
00898 Transform<Scalar,Dim,Mode,Options>::prerotate(const RotationType& rotation)
00899 {
00900 m_matrix.template block<Dim,HDim>(0,0) = internal::toRotationMatrix<Scalar,Dim>(rotation)
00901 * m_matrix.template block<Dim,HDim>(0,0);
00902 return *this;
00903 }
00904
00910 template<typename Scalar, int Dim, int Mode, int Options>
00911 Transform<Scalar,Dim,Mode,Options>&
00912 Transform<Scalar,Dim,Mode,Options>::shear(Scalar sx, Scalar sy)
00913 {
00914 EIGEN_STATIC_ASSERT(int(Dim)==2, YOU_MADE_A_PROGRAMMING_MISTAKE)
00915 EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)
00916 VectorType tmp = linear().col(0)*sy + linear().col(1);
00917 linear() << linear().col(0) + linear().col(1)*sx, tmp;
00918 return *this;
00919 }
00920
00926 template<typename Scalar, int Dim, int Mode, int Options>
00927 Transform<Scalar,Dim,Mode,Options>&
00928 Transform<Scalar,Dim,Mode,Options>::preshear(Scalar sx, Scalar sy)
00929 {
00930 EIGEN_STATIC_ASSERT(int(Dim)==2, YOU_MADE_A_PROGRAMMING_MISTAKE)
00931 EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)
00932 m_matrix.template block<Dim,HDim>(0,0) = LinearMatrixType(1, sx, sy, 1) * m_matrix.template block<Dim,HDim>(0,0);
00933 return *this;
00934 }
00935
00936
00937
00938
00939
00940 template<typename Scalar, int Dim, int Mode, int Options>
00941 inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const TranslationType& t)
00942 {
00943 linear().setIdentity();
00944 translation() = t.vector();
00945 makeAffine();
00946 return *this;
00947 }
00948
00949 template<typename Scalar, int Dim, int Mode, int Options>
00950 inline Transform<Scalar,Dim,Mode,Options> Transform<Scalar,Dim,Mode,Options>::operator*(const TranslationType& t) const
00951 {
00952 Transform res = *this;
00953 res.translate(t.vector());
00954 return res;
00955 }
00956
00957 template<typename Scalar, int Dim, int Mode, int Options>
00958 inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const UniformScaling<Scalar>& s)
00959 {
00960 m_matrix.setZero();
00961 linear().diagonal().fill(s.factor());
00962 makeAffine();
00963 return *this;
00964 }
00965
00966 template<typename Scalar, int Dim, int Mode, int Options>
00967 template<typename Derived>
00968 inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const RotationBase<Derived,Dim>& r)
00969 {
00970 linear() = internal::toRotationMatrix<Scalar,Dim>(r);
00971 translation().setZero();
00972 makeAffine();
00973 return *this;
00974 }
00975
00976 template<typename Scalar, int Dim, int Mode, int Options>
00977 template<typename Derived>
00978 inline Transform<Scalar,Dim,Mode,Options> Transform<Scalar,Dim,Mode,Options>::operator*(const RotationBase<Derived,Dim>& r) const
00979 {
00980 Transform res = *this;
00981 res.rotate(r.derived());
00982 return res;
00983 }
00984
00985
00986
00987
00988
00996 template<typename Scalar, int Dim, int Mode, int Options>
00997 const typename Transform<Scalar,Dim,Mode,Options>::LinearMatrixType
00998 Transform<Scalar,Dim,Mode,Options>::rotation() const
00999 {
01000 LinearMatrixType result;
01001 computeRotationScaling(&result, (LinearMatrixType*)0);
01002 return result;
01003 }
01004
01005
01017 template<typename Scalar, int Dim, int Mode, int Options>
01018 template<typename RotationMatrixType, typename ScalingMatrixType>
01019 void Transform<Scalar,Dim,Mode,Options>::computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const
01020 {
01021 JacobiSVD<LinearMatrixType> svd(linear(), ComputeFullU | ComputeFullV);
01022
01023 Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant();
01024 VectorType sv(svd.singularValues());
01025 sv.coeffRef(0) *= x;
01026 if(scaling) scaling->lazyAssign(svd.matrixV() * sv.asDiagonal() * svd.matrixV().adjoint());
01027 if(rotation)
01028 {
01029 LinearMatrixType m(svd.matrixU());
01030 m.col(0) /= x;
01031 rotation->lazyAssign(m * svd.matrixV().adjoint());
01032 }
01033 }
01034
01046 template<typename Scalar, int Dim, int Mode, int Options>
01047 template<typename ScalingMatrixType, typename RotationMatrixType>
01048 void Transform<Scalar,Dim,Mode,Options>::computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const
01049 {
01050 JacobiSVD<LinearMatrixType> svd(linear(), ComputeFullU | ComputeFullV);
01051
01052 Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant();
01053 VectorType sv(svd.singularValues());
01054 sv.coeffRef(0) *= x;
01055 if(scaling) scaling->lazyAssign(svd.matrixU() * sv.asDiagonal() * svd.matrixU().adjoint());
01056 if(rotation)
01057 {
01058 LinearMatrixType m(svd.matrixU());
01059 m.col(0) /= x;
01060 rotation->lazyAssign(m * svd.matrixV().adjoint());
01061 }
01062 }
01063
01067 template<typename Scalar, int Dim, int Mode, int Options>
01068 template<typename PositionDerived, typename OrientationType, typename ScaleDerived>
01069 Transform<Scalar,Dim,Mode,Options>&
01070 Transform<Scalar,Dim,Mode,Options>::fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,
01071 const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale)
01072 {
01073 linear() = internal::toRotationMatrix<Scalar,Dim>(orientation);
01074 linear() *= scale.asDiagonal();
01075 translation() = position;
01076 makeAffine();
01077 return *this;
01078 }
01079
01080 namespace internal {
01081
01082
01083 template<typename TransformType, int Mode=TransformType::Mode>
01084 struct projective_transform_inverse
01085 {
01086 static inline void run(const TransformType&, TransformType&)
01087 {}
01088 };
01089
01090 template<typename TransformType>
01091 struct projective_transform_inverse<TransformType, Projective>
01092 {
01093 static inline void run(const TransformType& m, TransformType& res)
01094 {
01095 res.matrix() = m.matrix().inverse();
01096 }
01097 };
01098
01099 }
01100
01101
01122 template<typename Scalar, int Dim, int Mode, int Options>
01123 Transform<Scalar,Dim,Mode,Options>
01124 Transform<Scalar,Dim,Mode,Options>::inverse(TransformTraits hint) const
01125 {
01126 Transform res;
01127 if (hint == Projective)
01128 {
01129 internal::projective_transform_inverse<Transform>::run(*this, res);
01130 }
01131 else
01132 {
01133 if (hint == Isometry)
01134 {
01135 res.matrix().template topLeftCorner<Dim,Dim>() = linear().transpose();
01136 }
01137 else if(hint&Affine)
01138 {
01139 res.matrix().template topLeftCorner<Dim,Dim>() = linear().inverse();
01140 }
01141 else
01142 {
01143 eigen_assert(false && "Invalid transform traits in Transform::Inverse");
01144 }
01145
01146 res.matrix().template topRightCorner<Dim,1>()
01147 = - res.matrix().template topLeftCorner<Dim,Dim>() * translation();
01148 res.makeAffine();
01149 }
01150 return res;
01151 }
01152
01153 namespace internal {
01154
01155
01156
01157
01158
01159 template<typename TransformType> struct transform_take_affine_part {
01160 typedef typename TransformType::MatrixType MatrixType;
01161 typedef typename TransformType::AffinePart AffinePart;
01162 typedef typename TransformType::ConstAffinePart ConstAffinePart;
01163 static inline AffinePart run(MatrixType& m)
01164 { return m.template block<TransformType::Dim,TransformType::HDim>(0,0); }
01165 static inline ConstAffinePart run(const MatrixType& m)
01166 { return m.template block<TransformType::Dim,TransformType::HDim>(0,0); }
01167 };
01168
01169 template<typename Scalar, int Dim, int Options>
01170 struct transform_take_affine_part<Transform<Scalar,Dim,AffineCompact, Options> > {
01171 typedef typename Transform<Scalar,Dim,AffineCompact,Options>::MatrixType MatrixType;
01172 static inline MatrixType& run(MatrixType& m) { return m; }
01173 static inline const MatrixType& run(const MatrixType& m) { return m; }
01174 };
01175
01176
01177
01178
01179
01180 template<typename Other, int Mode, int Options, int Dim, int HDim>
01181 struct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, Dim,Dim>
01182 {
01183 static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)
01184 {
01185 transform->linear() = other;
01186 transform->translation().setZero();
01187 transform->makeAffine();
01188 }
01189 };
01190
01191 template<typename Other, int Mode, int Options, int Dim, int HDim>
01192 struct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, Dim,HDim>
01193 {
01194 static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)
01195 {
01196 transform->affine() = other;
01197 transform->makeAffine();
01198 }
01199 };
01200
01201 template<typename Other, int Mode, int Options, int Dim, int HDim>
01202 struct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, HDim,HDim>
01203 {
01204 static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)
01205 { transform->matrix() = other; }
01206 };
01207
01208 template<typename Other, int Options, int Dim, int HDim>
01209 struct transform_construct_from_matrix<Other, AffineCompact,Options,Dim,HDim, HDim,HDim>
01210 {
01211 static inline void run(Transform<typename Other::Scalar,Dim,AffineCompact,Options> *transform, const Other& other)
01212 { transform->matrix() = other.template block<Dim,HDim>(0,0); }
01213 };
01214
01215
01216
01217
01218
01219 template<int LhsMode,int RhsMode>
01220 struct transform_product_result
01221 {
01222 enum
01223 {
01224 Mode =
01225 (LhsMode == (int)Projective || RhsMode == (int)Projective ) ? Projective :
01226 (LhsMode == (int)Affine || RhsMode == (int)Affine ) ? Affine :
01227 (LhsMode == (int)AffineCompact || RhsMode == (int)AffineCompact ) ? AffineCompact :
01228 (LhsMode == (int)Isometry || RhsMode == (int)Isometry ) ? Isometry : Projective
01229 };
01230 };
01231
01232 template< typename TransformType, typename MatrixType >
01233 struct transform_right_product_impl< TransformType, MatrixType, 0 >
01234 {
01235 typedef typename MatrixType::PlainObject ResultType;
01236
01237 static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)
01238 {
01239 return T.matrix() * other;
01240 }
01241 };
01242
01243 template< typename TransformType, typename MatrixType >
01244 struct transform_right_product_impl< TransformType, MatrixType, 1 >
01245 {
01246 enum {
01247 Dim = TransformType::Dim,
01248 HDim = TransformType::HDim,
01249 OtherRows = MatrixType::RowsAtCompileTime,
01250 OtherCols = MatrixType::ColsAtCompileTime
01251 };
01252
01253 typedef typename MatrixType::PlainObject ResultType;
01254
01255 static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)
01256 {
01257 EIGEN_STATIC_ASSERT(OtherRows==HDim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);
01258
01259 typedef Block<ResultType, Dim, OtherCols, int(MatrixType::RowsAtCompileTime)==Dim> TopLeftLhs;
01260
01261 ResultType res(other.rows(),other.cols());
01262 TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() = T.affine() * other;
01263 res.row(OtherRows-1) = other.row(OtherRows-1);
01264
01265 return res;
01266 }
01267 };
01268
01269 template< typename TransformType, typename MatrixType >
01270 struct transform_right_product_impl< TransformType, MatrixType, 2 >
01271 {
01272 enum {
01273 Dim = TransformType::Dim,
01274 HDim = TransformType::HDim,
01275 OtherRows = MatrixType::RowsAtCompileTime,
01276 OtherCols = MatrixType::ColsAtCompileTime
01277 };
01278
01279 typedef typename MatrixType::PlainObject ResultType;
01280
01281 static EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)
01282 {
01283 EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);
01284
01285 typedef Block<ResultType, Dim, OtherCols, true> TopLeftLhs;
01286 ResultType res(Replicate<typename TransformType::ConstTranslationPart, 1, OtherCols>(T.translation(),1,other.cols()));
01287 TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() += T.linear() * other;
01288
01289 return res;
01290 }
01291 };
01292
01293
01294
01295
01296
01297
01298 template<typename Other,int Mode, int Options, int Dim, int HDim>
01299 struct transform_left_product_impl<Other,Mode,Options,Dim,HDim, HDim,HDim>
01300 {
01301 typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;
01302 typedef typename TransformType::MatrixType MatrixType;
01303 typedef Transform<typename Other::Scalar,Dim,Projective,Options> ResultType;
01304 static ResultType run(const Other& other,const TransformType& tr)
01305 { return ResultType(other * tr.matrix()); }
01306 };
01307
01308
01309 template<typename Other, int Options, int Dim, int HDim>
01310 struct transform_left_product_impl<Other,AffineCompact,Options,Dim,HDim, HDim,HDim>
01311 {
01312 typedef Transform<typename Other::Scalar,Dim,AffineCompact,Options> TransformType;
01313 typedef typename TransformType::MatrixType MatrixType;
01314 typedef Transform<typename Other::Scalar,Dim,Projective,Options> ResultType;
01315 static ResultType run(const Other& other,const TransformType& tr)
01316 {
01317 ResultType res;
01318 res.matrix().noalias() = other.template block<HDim,Dim>(0,0) * tr.matrix();
01319 res.matrix().col(Dim) += other.col(Dim);
01320 return res;
01321 }
01322 };
01323
01324
01325 template<typename Other,int Mode, int Options, int Dim, int HDim>
01326 struct transform_left_product_impl<Other,Mode,Options,Dim,HDim, Dim,HDim>
01327 {
01328 typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;
01329 typedef typename TransformType::MatrixType MatrixType;
01330 typedef TransformType ResultType;
01331 static ResultType run(const Other& other,const TransformType& tr)
01332 {
01333 ResultType res;
01334 res.affine().noalias() = other * tr.matrix();
01335 res.matrix().row(Dim) = tr.matrix().row(Dim);
01336 return res;
01337 }
01338 };
01339
01340
01341 template<typename Other, int Options, int Dim, int HDim>
01342 struct transform_left_product_impl<Other,AffineCompact,Options,Dim,HDim, Dim,HDim>
01343 {
01344 typedef Transform<typename Other::Scalar,Dim,AffineCompact,Options> TransformType;
01345 typedef typename TransformType::MatrixType MatrixType;
01346 typedef TransformType ResultType;
01347 static ResultType run(const Other& other,const TransformType& tr)
01348 {
01349 ResultType res;
01350 res.matrix().noalias() = other.template block<Dim,Dim>(0,0) * tr.matrix();
01351 res.translation() += other.col(Dim);
01352 return res;
01353 }
01354 };
01355
01356
01357 template<typename Other,int Mode, int Options, int Dim, int HDim>
01358 struct transform_left_product_impl<Other,Mode,Options,Dim,HDim, Dim,Dim>
01359 {
01360 typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;
01361 typedef typename TransformType::MatrixType MatrixType;
01362 typedef TransformType ResultType;
01363 static ResultType run(const Other& other, const TransformType& tr)
01364 {
01365 TransformType res;
01366 if(Mode!=int(AffineCompact))
01367 res.matrix().row(Dim) = tr.matrix().row(Dim);
01368 res.matrix().template topRows<Dim>().noalias()
01369 = other * tr.matrix().template topRows<Dim>();
01370 return res;
01371 }
01372 };
01373
01374
01375
01376
01377
01378 template<typename Scalar, int Dim, int LhsMode, int LhsOptions, int RhsMode, int RhsOptions>
01379 struct transform_transform_product_impl<Transform<Scalar,Dim,LhsMode,LhsOptions>,Transform<Scalar,Dim,RhsMode,RhsOptions>,false >
01380 {
01381 enum { ResultMode = transform_product_result<LhsMode,RhsMode>::Mode };
01382 typedef Transform<Scalar,Dim,LhsMode,LhsOptions> Lhs;
01383 typedef Transform<Scalar,Dim,RhsMode,RhsOptions> Rhs;
01384 typedef Transform<Scalar,Dim,ResultMode,LhsOptions> ResultType;
01385 static ResultType run(const Lhs& lhs, const Rhs& rhs)
01386 {
01387 ResultType res;
01388 res.linear() = lhs.linear() * rhs.linear();
01389 res.translation() = lhs.linear() * rhs.translation() + lhs.translation();
01390 res.makeAffine();
01391 return res;
01392 }
01393 };
01394
01395 template<typename Scalar, int Dim, int LhsMode, int LhsOptions, int RhsMode, int RhsOptions>
01396 struct transform_transform_product_impl<Transform<Scalar,Dim,LhsMode,LhsOptions>,Transform<Scalar,Dim,RhsMode,RhsOptions>,true >
01397 {
01398 typedef Transform<Scalar,Dim,LhsMode,LhsOptions> Lhs;
01399 typedef Transform<Scalar,Dim,RhsMode,RhsOptions> Rhs;
01400 typedef Transform<Scalar,Dim,Projective> ResultType;
01401 static ResultType run(const Lhs& lhs, const Rhs& rhs)
01402 {
01403 return ResultType( lhs.matrix() * rhs.matrix() );
01404 }
01405 };
01406
01407 template<typename Scalar, int Dim, int LhsOptions, int RhsOptions>
01408 struct transform_transform_product_impl<Transform<Scalar,Dim,AffineCompact,LhsOptions>,Transform<Scalar,Dim,Projective,RhsOptions>,true >
01409 {
01410 typedef Transform<Scalar,Dim,AffineCompact,LhsOptions> Lhs;
01411 typedef Transform<Scalar,Dim,Projective,RhsOptions> Rhs;
01412 typedef Transform<Scalar,Dim,Projective> ResultType;
01413 static ResultType run(const Lhs& lhs, const Rhs& rhs)
01414 {
01415 ResultType res;
01416 res.matrix().template topRows<Dim>() = lhs.matrix() * rhs.matrix();
01417 res.matrix().row(Dim) = rhs.matrix().row(Dim);
01418 return res;
01419 }
01420 };
01421
01422 template<typename Scalar, int Dim, int LhsOptions, int RhsOptions>
01423 struct transform_transform_product_impl<Transform<Scalar,Dim,Projective,LhsOptions>,Transform<Scalar,Dim,AffineCompact,RhsOptions>,true >
01424 {
01425 typedef Transform<Scalar,Dim,Projective,LhsOptions> Lhs;
01426 typedef Transform<Scalar,Dim,AffineCompact,RhsOptions> Rhs;
01427 typedef Transform<Scalar,Dim,Projective> ResultType;
01428 static ResultType run(const Lhs& lhs, const Rhs& rhs)
01429 {
01430 ResultType res(lhs.matrix().template leftCols<Dim>() * rhs.matrix());
01431 res.matrix().col(Dim) += lhs.matrix().col(Dim);
01432 return res;
01433 }
01434 };
01435
01436 }
01437
01438 }
01439
01440 #endif // EIGEN_TRANSFORM_H