00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #ifndef EIGEN_ROTATIONBASE_H
00011 #define EIGEN_ROTATIONBASE_H
00012
00013 namespace Eigen {
00014
00015
00016 namespace internal {
00017 template<typename RotationDerived, typename MatrixType, bool IsVector=MatrixType::IsVectorAtCompileTime>
00018 struct rotation_base_generic_product_selector;
00019 }
00020
00028 template<typename Derived, int _Dim>
00029 class RotationBase
00030 {
00031 public:
00032 enum { Dim = _Dim };
00034 typedef typename internal::traits<Derived>::Scalar Scalar;
00035
00037 typedef Matrix<Scalar,Dim,Dim> RotationMatrixType;
00038 typedef Matrix<Scalar,Dim,1> VectorType;
00039
00040 public:
00041 inline const Derived& derived() const { return *static_cast<const Derived*>(this); }
00042 inline Derived& derived() { return *static_cast<Derived*>(this); }
00043
00045 inline RotationMatrixType toRotationMatrix() const { return derived().toRotationMatrix(); }
00046
00050 inline RotationMatrixType matrix() const { return derived().toRotationMatrix(); }
00051
00053 inline Derived inverse() const { return derived().inverse(); }
00054
00056 inline Transform<Scalar,Dim,Isometry> operator*(const Translation<Scalar,Dim>& t) const
00057 { return Transform<Scalar,Dim,Isometry>(*this) * t; }
00058
00060 inline RotationMatrixType operator*(const UniformScaling<Scalar>& s) const
00061 { return toRotationMatrix() * s.factor(); }
00062
00069 template<typename OtherDerived>
00070 EIGEN_STRONG_INLINE typename internal::rotation_base_generic_product_selector<Derived,OtherDerived,OtherDerived::IsVectorAtCompileTime>::ReturnType
00071 operator*(const EigenBase<OtherDerived>& e) const
00072 { return internal::rotation_base_generic_product_selector<Derived,OtherDerived>::run(derived(), e.derived()); }
00073
00075 template<typename OtherDerived> friend
00076 inline RotationMatrixType operator*(const EigenBase<OtherDerived>& l, const Derived& r)
00077 { return l.derived() * r.toRotationMatrix(); }
00078
00080 friend inline Transform<Scalar,Dim,Affine> operator*(const DiagonalMatrix<Scalar,Dim>& l, const Derived& r)
00081 {
00082 Transform<Scalar,Dim,Affine> res(r);
00083 res.linear().applyOnTheLeft(l);
00084 return res;
00085 }
00086
00088 template<int Mode, int Options>
00089 inline Transform<Scalar,Dim,Mode> operator*(const Transform<Scalar,Dim,Mode,Options>& t) const
00090 { return toRotationMatrix() * t; }
00091
00092 template<typename OtherVectorType>
00093 inline VectorType _transformVector(const OtherVectorType& v) const
00094 { return toRotationMatrix() * v; }
00095 };
00096
00097 namespace internal {
00098
00099
00100 template<typename RotationDerived, typename MatrixType>
00101 struct rotation_base_generic_product_selector<RotationDerived,MatrixType,false>
00102 {
00103 enum { Dim = RotationDerived::Dim };
00104 typedef Matrix<typename RotationDerived::Scalar,Dim,Dim> ReturnType;
00105 static inline ReturnType run(const RotationDerived& r, const MatrixType& m)
00106 { return r.toRotationMatrix() * m; }
00107 };
00108
00109 template<typename RotationDerived, typename Scalar, int Dim, int MaxDim>
00110 struct rotation_base_generic_product_selector< RotationDerived, DiagonalMatrix<Scalar,Dim,MaxDim>, false >
00111 {
00112 typedef Transform<Scalar,Dim,Affine> ReturnType;
00113 static inline ReturnType run(const RotationDerived& r, const DiagonalMatrix<Scalar,Dim,MaxDim>& m)
00114 {
00115 ReturnType res(r);
00116 res.linear() *= m;
00117 return res;
00118 }
00119 };
00120
00121 template<typename RotationDerived,typename OtherVectorType>
00122 struct rotation_base_generic_product_selector<RotationDerived,OtherVectorType,true>
00123 {
00124 enum { Dim = RotationDerived::Dim };
00125 typedef Matrix<typename RotationDerived::Scalar,Dim,1> ReturnType;
00126 static EIGEN_STRONG_INLINE ReturnType run(const RotationDerived& r, const OtherVectorType& v)
00127 {
00128 return r._transformVector(v);
00129 }
00130 };
00131
00132 }
00133
00138 template<typename _Scalar, int _Rows, int _Cols, int _Storage, int _MaxRows, int _MaxCols>
00139 template<typename OtherDerived>
00140 Matrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols>
00141 ::Matrix(const RotationBase<OtherDerived,ColsAtCompileTime>& r)
00142 {
00143 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix,int(OtherDerived::Dim),int(OtherDerived::Dim))
00144 *this = r.toRotationMatrix();
00145 }
00146
00151 template<typename _Scalar, int _Rows, int _Cols, int _Storage, int _MaxRows, int _MaxCols>
00152 template<typename OtherDerived>
00153 Matrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols>&
00154 Matrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols>
00155 ::operator=(const RotationBase<OtherDerived,ColsAtCompileTime>& r)
00156 {
00157 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix,int(OtherDerived::Dim),int(OtherDerived::Dim))
00158 return *this = r.toRotationMatrix();
00159 }
00160
00161 namespace internal {
00162
00181 template<typename Scalar, int Dim>
00182 static inline Matrix<Scalar,2,2> toRotationMatrix(const Scalar& s)
00183 {
00184 EIGEN_STATIC_ASSERT(Dim==2,YOU_MADE_A_PROGRAMMING_MISTAKE)
00185 return Rotation2D<Scalar>(s).toRotationMatrix();
00186 }
00187
00188 template<typename Scalar, int Dim, typename OtherDerived>
00189 static inline Matrix<Scalar,Dim,Dim> toRotationMatrix(const RotationBase<OtherDerived,Dim>& r)
00190 {
00191 return r.toRotationMatrix();
00192 }
00193
00194 template<typename Scalar, int Dim, typename OtherDerived>
00195 static inline const MatrixBase<OtherDerived>& toRotationMatrix(const MatrixBase<OtherDerived>& mat)
00196 {
00197 EIGEN_STATIC_ASSERT(OtherDerived::RowsAtCompileTime==Dim && OtherDerived::ColsAtCompileTime==Dim,
00198 YOU_MADE_A_PROGRAMMING_MISTAKE)
00199 return mat;
00200 }
00201
00202 }
00203
00204 }
00205
00206 #endif // EIGEN_ROTATIONBASE_H