11 #ifndef EIGEN_QUATERNION_H    12 #define EIGEN_QUATERNION_H    22 template<
typename Other,
    23          int OtherRows=Other::RowsAtCompileTime,
    24          int OtherCols=Other::ColsAtCompileTime>
    34 template<
class Derived>
    39   using Base::operator*;
    60   inline Scalar 
x()
 const { 
return this->derived().coeffs().coeff(0); }
    62   inline Scalar 
y()
 const { 
return this->derived().coeffs().coeff(1); }
    64   inline Scalar 
z()
 const { 
return this->derived().coeffs().coeff(2); }
    66   inline Scalar 
w()
 const { 
return this->derived().coeffs().coeff(3); }
    69   inline Scalar& 
x() { 
return this->derived().coeffs().coeffRef(0); }
    71   inline Scalar& 
y() { 
return this->derived().coeffs().coeffRef(1); }
    73   inline Scalar& 
z() { 
return this->derived().coeffs().coeffRef(2); }
    75   inline Scalar& 
w() { 
return this->derived().coeffs().coeffRef(3); }
    99   Derived& operator=(
const AngleAxisType& aa);
   114   inline Scalar 
squaredNorm()
 const { 
return coeffs().squaredNorm(); }
   119   inline Scalar 
norm()
 const { 
return coeffs().norm(); }
   141   template<
typename Derived1, 
typename Derived2>
   163   template<
class OtherDerived>
   165   { 
return coeffs().isApprox(other.
coeffs(), prec); }
   175   template<
typename NewScalarType>
   181 #ifdef EIGEN_QUATERNIONBASE_PLUGIN   182 # include EIGEN_QUATERNIONBASE_PLUGIN   214 template<
typename _Scalar,
int _Options>
   227 template<
typename _Scalar, 
int _Options>
   237   using Base::operator*=;
   240   typedef typename Base::AngleAxisType AngleAxisType;
   252   inline Quaternion(
const Scalar& w, 
const Scalar& x, 
const Scalar& 
y, 
const Scalar& z) : m_coeffs(x, y, z, w){}
   261   explicit inline Quaternion(
const AngleAxisType& aa) { *
this = aa; }
   267   template<
typename Derived>
   271   template<
typename OtherScalar, 
int OtherOptions>
   273   { m_coeffs = other.
coeffs().template cast<Scalar>(); }
   275   template<
typename Derived1, 
typename Derived2>
   278   inline Coefficients& 
coeffs() { 
return m_coeffs;}
   279   inline const Coefficients& 
coeffs()
 const { 
return m_coeffs;}
   284   Coefficients m_coeffs;
   286 #ifndef EIGEN_PARSED_BY_DOXYGEN   290         INVALID_MATRIX_TEMPLATE_PARAMETERS)
   307   template<
typename _Scalar, 
int _Options>
   308   struct traits<
Map<
Quaternion<_Scalar>, _Options> > : 
traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> >
   315   template<
typename _Scalar, 
int _Options>
   316   struct traits<
Map<const 
Quaternion<_Scalar>, _Options> > : 
traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> >
   337 template<
typename _Scalar, 
int _Options>
   339   : 
public QuaternionBase<Map<const Quaternion<_Scalar>, _Options> >
   347     using Base::operator*=;
   357     inline const Coefficients& 
coeffs()
 const { 
return m_coeffs;}
   374 template<
typename _Scalar, 
int _Options>
   384     using Base::operator*=;
   394     inline Coefficients& 
coeffs() { 
return m_coeffs; }
   395     inline const Coefficients& 
coeffs()
 const { 
return m_coeffs; }
   421 template<
int Arch, 
class Derived1, 
class Derived2, 
typename Scalar, 
int _Options> 
struct quat_product   426       a.
w() * b.
w() - a.
x() * b.
x() - a.
y() * b.
y() - a.
z() * b.
z(),
   427       a.
w() * b.
x() + a.
x() * b.
w() + a.
y() * b.
z() - a.
z() * b.
y(),
   428       a.
w() * b.
y() + a.
y() * b.
w() + a.
z() * b.
x() - a.
x() * b.
z(),
   429       a.
w() * b.
z() + a.
z() * b.
w() + a.
x() * b.
y() - a.
y() * b.
x()
   436 template <
class Derived>
   437 template <
class OtherDerived>
   442    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
   449 template <
class Derived>
   450 template <
class OtherDerived>
   453   derived() = derived() * other.
derived();
   464 template <
class Derived>
   473     Vector3 uv = this->vec().cross(v);
   475     return v + this->
w() * uv + this->vec().cross(uv);
   478 template<
class Derived>
   481   coeffs() = other.
coeffs();
   485 template<
class Derived>
   486 template<
class OtherDerived>
   489   coeffs() = other.
coeffs();
   495 template<
class Derived>
   500   Scalar ha = Scalar(0.5)*aa.
angle(); 
   502   this->vec() = 
sin(ha) * aa.
axis();
   512 template<
class Derived>
   513 template<
class MatrixDerived>
   517    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
   525 template<
class Derived>
   535   const Scalar tx  = Scalar(2)*this->
x();
   536   const Scalar ty  = Scalar(2)*this->
y();
   537   const Scalar tz  = Scalar(2)*this->
z();
   538   const Scalar twx = tx*this->
w();
   539   const Scalar twy = ty*this->w();
   540   const Scalar twz = tz*this->w();
   541   const Scalar txx = tx*this->
x();
   542   const Scalar txy = ty*this->x();
   543   const Scalar txz = tz*this->x();
   544   const Scalar tyy = ty*this->
y();
   545   const Scalar tyz = tz*this->
y();
   546   const Scalar tzz = tz*this->
z();
   548   res.
coeffRef(0,0) = Scalar(1)-(tyy+tzz);
   552   res.
coeffRef(1,1) = Scalar(1)-(txx+tzz);
   556   res.
coeffRef(2,2) = Scalar(1)-(txx+tyy);
   571 template<
class Derived>
   572 template<
typename Derived1, 
typename Derived2>
   579   Scalar c = v1.dot(v0);
   591     c = max<Scalar>(c,-1);
   596     Scalar w2 = (Scalar(1)+c)*Scalar(0.5);
   597     this->
w() = 
sqrt(w2);
   598     this->vec() = axis * 
sqrt(Scalar(1) - w2);
   601   Vector3 
axis = v0.cross(v1);
   602   Scalar 
s = 
sqrt((Scalar(1)+c)*Scalar(2));
   603   Scalar invs = Scalar(1)/s;
   604   this->vec() = axis * invs;
   605   this->
w() = s * Scalar(0.5);
   621 template<
typename Scalar, 
int Options>
   622 template<
typename Derived1, 
typename Derived2>
   637 template <
class Derived>
   641   Scalar n2 = this->squaredNorm();
   657 template <
class Derived>
   667 template <
class Derived>
   668 template <
class OtherDerived>
   674   double d = 
abs(this->
dot(other));
   677   return static_cast<Scalar
>(2 * 
acos(d));
   683 template <
class Derived>
   684 template <
class OtherDerived>
   692   Scalar 
d = this->
dot(other);
   693   Scalar absD = 
abs(d);
   700     scale0 = Scalar(1) - t;
   706     Scalar theta = 
acos(absD);
   707     Scalar sinTheta = 
sin(theta);
   709     scale0 = 
sin( ( Scalar(1) - t ) * theta) / sinTheta;
   710     scale1 = 
sin( ( t * theta) ) / sinTheta;
   712   if(d<0) scale1 = -scale1;
   720 template<
typename Other>
   730     Scalar t = mat.trace();
   733       t = 
sqrt(t + Scalar(1.0));
   734       q.
w() = Scalar(0.5)*t;
   736       q.
x() = (mat.coeff(2,1) - mat.coeff(1,2)) * t;
   737       q.
y() = (mat.coeff(0,2) - mat.coeff(2,0)) * t;
   738       q.
z() = (mat.coeff(1,0) - mat.coeff(0,1)) * t;
   743       if (mat.coeff(1,1) > mat.coeff(0,0))
   745       if (mat.coeff(2,2) > mat.coeff(i,i))
   750       t = 
sqrt(mat.coeff(i,i)-mat.coeff(j,j)-mat.coeff(k,k) + Scalar(1.0));
   751       q.
coeffs().coeffRef(i) = Scalar(0.5) * t;
   753       q.
w() = (mat.coeff(k,j)-mat.coeff(j,k))*t;
   754       q.
coeffs().coeffRef(j) = (mat.coeff(j,i)+mat.coeff(i,j))*t;
   755       q.
coeffs().coeffRef(k) = (mat.coeff(k,i)+mat.coeff(i,k))*t;
   761 template<
typename Other>
   775 #endif // EIGEN_QUATERNION_H 
internal::traits< Derived >::Coefficients Coefficients
QuaternionBase< Quaternion< _Scalar, _Options > > Base
Scalar dot(const QuaternionBase< OtherDerived > &other) const 
const Coefficients & coeffs() const 
#define EIGEN_STRONG_INLINE
static void run(QuaternionBase< Derived > &q, const Other &vec)
static Matrix< Scalar, 2, 2 > toRotationMatrix(const Scalar &s)
#define EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived)
NumTraits< Scalar >::Real RealScalar
Quaternion< _Scalar, _Options > PlainObject
A matrix or vector expression mapping an existing array of data. 
Matrix< Scalar, 3, 1 > Vector3
const Coefficients & coeffs() const 
const unsigned int LvalueBit
EIGEN_STRONG_INLINE Quaternion< Scalar > operator*(const QuaternionBase< OtherDerived > &q) const 
const VectorBlock< const Coefficients, 3 > vec() const 
internal::cast_return_type< Derived, Quaternion< NewScalarType > >::type cast() const 
const internal::traits< Derived >::Coefficients & coeffs() const 
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
const internal::permut_matrix_product_retval< PermutationDerived, Derived, OnTheRight > operator*(const MatrixBase< Derived > &matrix, const PermutationBase< PermutationDerived > &permutation)
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
Quaternion(const Quaternion< OtherScalar, OtherOptions > &other)
AngleAxis< Scalar > AngleAxisType
static Quaternion< Scalar > Identity()
TFSIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
Map< const Matrix< _Scalar, 4, 1 >, _Options > Coefficients
Scalar squaredNorm() const 
const Vector3 & axis() const 
Quaternion< Scalar > slerp(const Scalar &t, const QuaternionBase< OtherDerived > &other) const 
Derived & setFromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
EIGEN_STRONG_INLINE const CwiseUnaryOp< internal::scalar_abs_op< Scalar >, const Derived > abs() const 
const unsigned int AlignedBit
const CwiseUnaryOp< internal::scalar_inverse_op< Scalar >, const Derived > inverse() const 
Expression of a fixed-size or dynamic-size sub-vector. 
EIGEN_STRONG_INLINE Derived & operator*=(const QuaternionBase< OtherDerived > &q)
static EIGEN_STRONG_INLINE void _check_template_params()
internal::traits< Derived >::Coefficients & coeffs()
Map< Matrix< _Scalar, 4, 1 >, _Options > Coefficients
traits< Quaternion< _Scalar,(int(_Options)&Aligned)==Aligned?AutoAlign:DontAlign > > TraitsBase
Quaternion(const MatrixBase< Derived > &other)
EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
EIGEN_STRONG_INLINE Quaternion(const QuaternionBase< Derived > &other)
Quaternion(const Scalar &w, const Scalar &x, const Scalar &y, const Scalar &z)
bool isApprox(const QuaternionBase< OtherDerived > &other, const RealScalar &prec=NumTraits< Scalar >::dummy_precision()) const 
const PlainObject normalized() const 
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
Common base class for compact rotation representations. 
Scalar angularDistance(const QuaternionBase< OtherDerived > &other) const 
Quaternion< Scalar > conjugate() const 
TFSIMD_FORCE_INLINE const tfScalar & x() const 
const CwiseUnaryOp< internal::scalar_sin_op< Scalar >, const Derived > sin() const 
ConjugateReturnType conjugate() const 
Base class for quaternion expressions. 
internal::traits< Map >::Coefficients Coefficients
static EIGEN_STRONG_INLINE Quaternion< Scalar > run(const QuaternionBase< Derived1 > &a, const QuaternionBase< Derived2 > &b)
const Coefficients m_coeffs
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
static Quaternion FromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
QuaternionBase< Map< const Quaternion< _Scalar >, _Options > > Base
TFSIMD_FORCE_INLINE const tfScalar & z() const 
Quaternion< Scalar > inverse() const 
EIGEN_DEFAULT_DENSE_INDEX_TYPE DenseIndex
Map< Quaternion< float >, 0 > QuaternionMapf
TFSIMD_FORCE_INLINE const tfScalar & w() const 
Matrix< _Scalar, 4, 1, _Options > Coefficients
The quaternion class used to represent 3D orientations and rotations. 
const Coefficients & coeffs() const 
RotationBase< Derived, 3 > Base
Map< Quaternion< double >, 0 > QuaternionMapd
Two-sided Jacobi SVD decomposition of a rectangular matrix. 
Matrix3 toRotationMatrix() const 
EIGEN_STRONG_INLINE Vector3 _transformVector(Vector3 v) const 
Map< Quaternion< float >, Aligned > QuaternionMapAlignedf
const CwiseUnaryOp< internal::scalar_cos_op< Scalar >, const Derived > cos() const 
Quaternion(const AngleAxisType &aa)
QuaternionBase & setIdentity()
const Derived & derived() const
Quaternion< double > Quaterniond
Quaternion< Scalar > normalized() const 
Quaternion(const Scalar *data)
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const 
internal::traits< Map >::Coefficients Coefficients
Matrix< Scalar, 3, 3 > Matrix3
VectorBlock< Coefficients, 3 > vec()
const CwiseUnaryOp< internal::scalar_acos_op< Scalar >, const Derived > acos() const 
Quaternion< float > Quaternionf
internal::traits< Derived >::Scalar Scalar
EIGEN_STRONG_INLINE QuaternionBase< Derived > & operator=(const QuaternionBase< Derived > &other)
Base class for all dense matrices, vectors, and expressions. 
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis. 
const MatrixVType & matrixV() const 
Map< Quaternion< double >, Aligned > QuaternionMapAlignedd
static void run(QuaternionBase< Derived > &q, const Other &mat)
QuaternionBase< Map< Quaternion< _Scalar >, _Options > > Base
Quaternion & setFromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)