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>
40 using Base::operator*;
61 EIGEN_DEVICE_FUNC
inline Scalar
x()
const {
return this->derived().coeffs().coeff(0); }
63 EIGEN_DEVICE_FUNC
inline Scalar
y()
const {
return this->derived().coeffs().coeff(1); }
65 EIGEN_DEVICE_FUNC
inline Scalar
z()
const {
return this->derived().coeffs().coeff(2); }
67 EIGEN_DEVICE_FUNC
inline Scalar
w()
const {
return this->derived().coeffs().coeff(3); }
70 EIGEN_DEVICE_FUNC
inline Scalar&
x() {
return this->derived().coeffs().coeffRef(0); }
72 EIGEN_DEVICE_FUNC
inline Scalar&
y() {
return this->derived().coeffs().coeffRef(1); }
74 EIGEN_DEVICE_FUNC
inline Scalar&
z() {
return this->derived().coeffs().coeffRef(2); }
76 EIGEN_DEVICE_FUNC
inline Scalar&
w() {
return this->derived().coeffs().coeffRef(3); }
100 EIGEN_DEVICE_FUNC Derived& operator=(
const AngleAxisType& aa);
115 EIGEN_DEVICE_FUNC
inline Scalar
squaredNorm()
const {
return coeffs().squaredNorm(); }
120 EIGEN_DEVICE_FUNC
inline Scalar
norm()
const {
return coeffs().norm(); }
124 EIGEN_DEVICE_FUNC
inline void normalize() { coeffs().normalize(); }
142 template<
typename Derived1,
typename Derived2>
160 template<
class OtherDerived>
162 {
return coeffs().isApprox(other.
coeffs(), prec); }
172 template<
typename NewScalarType>
178 #ifdef EIGEN_QUATERNIONBASE_PLUGIN 179 # include EIGEN_QUATERNIONBASE_PLUGIN 213 template<
typename _Scalar,
int _Options>
226 template<
typename _Scalar,
int _Options>
236 using Base::operator*=;
239 typedef typename Base::AngleAxisType AngleAxisType;
251 EIGEN_DEVICE_FUNC
inline Quaternion(
const Scalar& w,
const Scalar& x,
const Scalar&
y,
const Scalar& z) : m_coeffs(x, y, z, w){}
254 EIGEN_DEVICE_FUNC
explicit inline Quaternion(
const Scalar* data) : m_coeffs(data) {}
260 EIGEN_DEVICE_FUNC
explicit inline Quaternion(
const AngleAxisType& aa) { *
this = aa; }
266 template<
typename Derived>
270 template<
typename OtherScalar,
int OtherOptions>
272 { m_coeffs = other.
coeffs().template cast<Scalar>(); }
274 EIGEN_DEVICE_FUNC
static Quaternion UnitRandom();
276 template<
typename Derived1,
typename Derived2>
279 EIGEN_DEVICE_FUNC
inline Coefficients&
coeffs() {
return m_coeffs;}
280 EIGEN_DEVICE_FUNC
inline const Coefficients&
coeffs()
const {
return m_coeffs;}
284 #ifdef EIGEN_QUATERNION_PLUGIN 285 # include EIGEN_QUATERNION_PLUGIN 291 #ifndef EIGEN_PARSED_BY_DOXYGEN 295 INVALID_MATRIX_TEMPLATE_PARAMETERS)
312 template<
typename _Scalar,
int _Options>
313 struct traits<
Map<
Quaternion<_Scalar>, _Options> > :
traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> >
320 template<
typename _Scalar,
int _Options>
321 struct traits<
Map<const
Quaternion<_Scalar>, _Options> > :
traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> >
342 template<
typename _Scalar,
int _Options>
344 :
public QuaternionBase<Map<const Quaternion<_Scalar>, _Options> >
352 using Base::operator*=;
362 EIGEN_DEVICE_FUNC
inline const Coefficients&
coeffs()
const {
return m_coeffs;}
379 template<
typename _Scalar,
int _Options>
389 using Base::operator*=;
399 EIGEN_DEVICE_FUNC
inline Coefficients&
coeffs() {
return m_coeffs; }
400 EIGEN_DEVICE_FUNC
inline const Coefficients&
coeffs()
const {
return m_coeffs; }
426 template<
int Arch,
class Derived1,
class Derived2,
typename Scalar>
struct quat_product 431 a.
w() * b.
w() - a.
x() * b.
x() - a.
y() * b.
y() - a.
z() * b.
z(),
432 a.
w() * b.
x() + a.
x() * b.
w() + a.
y() * b.
z() - a.
z() * b.
y(),
433 a.
w() * b.
y() + a.
y() * b.
w() + a.
z() * b.
x() - a.
x() * b.
z(),
434 a.
w() * b.
z() + a.
z() * b.
w() + a.
x() * b.
y() - a.
y() * b.
x()
441 template <
class Derived>
442 template <
class OtherDerived>
447 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
453 template <
class Derived>
454 template <
class OtherDerived>
457 derived() = derived() * other.
derived();
468 template <
class Derived>
477 Vector3 uv = this->vec().cross(v);
479 return v + this->
w() * uv + this->vec().cross(uv);
482 template<
class Derived>
485 coeffs() = other.
coeffs();
489 template<
class Derived>
490 template<
class OtherDerived>
493 coeffs() = other.
coeffs();
499 template<
class Derived>
502 EIGEN_USING_STD_MATH(
cos)
503 EIGEN_USING_STD_MATH(
sin)
504 Scalar ha = Scalar(0.5)*aa.
angle();
506 this->vec() =
sin(ha) * aa.
axis();
516 template<
class Derived>
517 template<
class MatrixDerived>
521 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
529 template<
class Derived>
539 const Scalar tx = Scalar(2)*this->x();
540 const Scalar ty = Scalar(2)*this->
y();
541 const Scalar tz = Scalar(2)*this->
z();
542 const Scalar twx = tx*this->
w();
543 const Scalar twy = ty*this->w();
544 const Scalar twz = tz*this->w();
545 const Scalar txx = tx*this->x();
546 const Scalar txy = ty*this->x();
547 const Scalar txz = tz*this->x();
548 const Scalar tyy = ty*this->
y();
549 const Scalar tyz = tz*this->
y();
550 const Scalar tzz = tz*this->
z();
552 res.
coeffRef(0,0) = Scalar(1)-(tyy+tzz);
556 res.
coeffRef(1,1) = Scalar(1)-(txx+tzz);
560 res.
coeffRef(2,2) = Scalar(1)-(txx+tyy);
575 template<
class Derived>
576 template<
typename Derived1,
typename Derived2>
579 EIGEN_USING_STD_MATH(
sqrt)
582 Scalar c = v1.dot(v0);
594 c = numext::maxi(c,Scalar(-1));
597 Vector3 axis = svd.
matrixV().col(2);
599 Scalar w2 = (Scalar(1)+c)*Scalar(0.5);
600 this->
w() =
sqrt(w2);
601 this->vec() = axis *
sqrt(Scalar(1) - w2);
604 Vector3 axis = v0.cross(v1);
605 Scalar
s =
sqrt((Scalar(1)+c)*Scalar(2));
606 Scalar invs = Scalar(1)/s;
607 this->vec() = axis * invs;
608 this->
w() = s * Scalar(0.5);
617 template<
typename Scalar,
int Options>
620 EIGEN_USING_STD_MATH(
sqrt)
621 EIGEN_USING_STD_MATH(
sin)
622 EIGEN_USING_STD_MATH(
cos)
623 const Scalar u1 = internal::random<Scalar>(0, 1),
624 u2 = internal::random<Scalar>(0, 2*
EIGEN_PI),
625 u3 = internal::random<Scalar>(0, 2*
EIGEN_PI);
626 const Scalar a =
sqrt(1 - u1),
642 template<
typename Scalar,
int Options>
643 template<
typename Derived1,
typename Derived2>
658 template <
class Derived>
662 Scalar n2 = this->squaredNorm();
674 template<
int Arch,
class Derived,
typename Scalar>
struct quat_conj 688 template <
class Derived>
700 template <
class Derived>
701 template <
class OtherDerived>
705 EIGEN_USING_STD_MATH(
atan2)
718 template <
class Derived>
719 template <
class OtherDerived>
723 EIGEN_USING_STD_MATH(
acos)
724 EIGEN_USING_STD_MATH(
sin)
726 Scalar
d = this->
dot(other);
734 scale0 = Scalar(1) - t;
740 Scalar theta =
acos(absD);
741 Scalar sinTheta =
sin(theta);
743 scale0 =
sin( ( Scalar(1) - t ) * theta) / sinTheta;
744 scale1 =
sin( ( t * theta) ) / sinTheta;
746 if(d<Scalar(0)) scale1 = -scale1;
754 template<
typename Other>
761 EIGEN_USING_STD_MATH(
sqrt)
764 Scalar t = mat.trace();
767 t =
sqrt(t + Scalar(1.0));
768 q.
w() = Scalar(0.5)*t;
770 q.
x() = (mat.coeff(2,1) - mat.coeff(1,2)) * t;
771 q.
y() = (mat.coeff(0,2) - mat.coeff(2,0)) * t;
772 q.
z() = (mat.coeff(1,0) - mat.coeff(0,1)) * t;
777 if (mat.coeff(1,1) > mat.coeff(0,0))
779 if (mat.coeff(2,2) > mat.coeff(i,i))
784 t =
sqrt(mat.coeff(i,i)-mat.coeff(j,j)-mat.coeff(k,k) + Scalar(1.0));
785 q.
coeffs().coeffRef(i) = Scalar(0.5) * t;
787 q.
w() = (mat.coeff(k,j)-mat.coeff(j,k))*t;
788 q.
coeffs().coeffRef(j) = (mat.coeff(j,i)+mat.coeff(i,j))*t;
789 q.
coeffs().coeffRef(k) = (mat.coeff(k,i)+mat.coeff(i,k))*t;
795 template<
typename Other>
809 #endif // EIGEN_QUATERNION_H EIGEN_DEVICE_FUNC Scalar z() const
EIGEN_DEVICE_FUNC Coefficients & coeffs()
internal::traits< Derived >::Coefficients Coefficients
EIGEN_DEVICE_FUNC internal::cast_return_type< Derived, Quaternion< NewScalarType > >::type cast() const
#define EIGEN_STRONG_INLINE
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half & operator*=(half &a, const half &b)
NumTraits< Scalar >::Real RealScalar
Quaternion< _Scalar, _Options > PlainObject
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion(const QuaternionBase< Derived > &other)
EIGEN_DEVICE_FUNC Quaternion< Scalar > normalized() const
A matrix or vector expression mapping an existing array of data.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & operator*=(const QuaternionBase< OtherDerived > &q)
Matrix< Scalar, 3, 1 > Vector3
Quaternion< double > Quaterniond
const unsigned int LvalueBit
EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
EIGEN_DEVICE_FUNC Quaternion(const Scalar &w, const Scalar &x, const Scalar &y, const Scalar &z)
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalar > run(const QuaternionBase< Derived > &q)
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
EIGEN_DEVICE_FUNC Quaternion< Scalar > conjugate() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const AbsReturnType abs() const
AngleAxis< Scalar > AngleAxisType
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalar > operator*(const QuaternionBase< OtherDerived > &q) const
EIGEN_DEVICE_FUNC const Coefficients & coeffs() const
EIGEN_DEVICE_FUNC Scalar & y()
TFSIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
Map< const Matrix< _Scalar, 4, 1 >, _Options > Coefficients
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
EIGEN_DEVICE_FUNC const Vector3 & axis() const
EIGEN_DEVICE_FUNC Quaternion(const MatrixBase< Derived > &other)
static EIGEN_DEVICE_FUNC void run(QuaternionBase< Derived > &q, const Other &vec)
EIGEN_DEVICE_FUNC Derived & setFromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
EIGEN_DEVICE_FUNC const VectorBlock< const Coefficients, 3 > vec() const
static EIGEN_STRONG_INLINE void _check_template_params()
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
EIGEN_DEVICE_FUNC const CosReturnType cos() const
EIGEN_DEVICE_FUNC Scalar angle() const
Expression of a fixed-size or dynamic-size sub-vector.
static EIGEN_DEVICE_FUNC Quaternion< Scalar > Identity()
EIGEN_DEVICE_FUNC const internal::traits< Derived >::Coefficients & coeffs() const
EIGEN_DEVICE_FUNC void normalize()
EIGEN_DEVICE_FUNC bool isApprox(const QuaternionBase< OtherDerived > &other, const RealScalar &prec=NumTraits< Scalar >::dummy_precision()) const
EIGEN_DEVICE_FUNC VectorBlock< Coefficients, 3 > vec()
EIGEN_DEVICE_FUNC const Coefficients & coeffs() const
EIGEN_DEVICE_FUNC Scalar w() const
Map< Matrix< _Scalar, 4, 1 >, _Options > Coefficients
traits< Quaternion< _Scalar,(int(_Options)&Aligned)==Aligned?AutoAlign:DontAlign > > TraitsBase
EIGEN_DEVICE_FUNC internal::traits< Derived >::Coefficients & coeffs()
static EIGEN_DEVICE_FUNC Matrix< Scalar, 2, 2 > toRotationMatrix(const Scalar &s)
EIGEN_DEVICE_FUNC Scalar dot(const QuaternionBase< OtherDerived > &other) const
EIGEN_DEVICE_FUNC ConjugateReturnType conjugate() const
EIGEN_DEVICE_FUNC Scalar angularDistance(const QuaternionBase< OtherDerived > &other) const
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
static EIGEN_DEVICE_FUNC Quaternion FromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
EIGEN_DEVICE_FUNC Quaternion(const Scalar *data)
EIGEN_DEVICE_FUNC const PlainObject normalized() const
Common base class for compact rotation representations.
const MatrixVType & matrixV() const
EIGEN_DEVICE_FUNC const Scalar & q
#define EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Derived)
EIGEN_DEVICE_FUNC Quaternion(const Quaternion< OtherScalar, OtherOptions > &other)
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorUInt128< uint64_t, uint64_t > operator*(const TensorUInt128< HL, LL > &lhs, const TensorUInt128< HR, LR > &rhs)
Base class for quaternion expressions.
internal::traits< Map >::Coefficients Coefficients
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase< Derived > & operator=(const QuaternionBase< Derived > &other)
EIGEN_DEVICE_FUNC Quaternion(const AngleAxisType &aa)
EIGEN_DEVICE_FUNC QuaternionBase & setIdentity()
const Coefficients m_coeffs
EIGEN_DEVICE_FUNC Scalar & z()
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
QuaternionBase< Map< const Quaternion< _Scalar >, _Options > > Base
TFSIMD_FORCE_INLINE const tfScalar & z() const
EIGEN_DEVICE_FUNC const Derived & derived() const
EIGEN_DEVICE_FUNC const AcosReturnType acos() const
Map< Quaternion< float >, 0 > QuaternionMapf
EIGEN_DEVICE_FUNC Coefficients & coeffs()
TFSIMD_FORCE_INLINE const tfScalar & w() const
Matrix< _Scalar, 4, 1, _Options > Coefficients
EIGEN_DEVICE_FUNC Scalar norm() const
EIGEN_DEVICE_FUNC const Coefficients & coeffs() const
The quaternion class used to represent 3D orientations and rotations.
RotationBase< Derived, 3 > Base
Map< Quaternion< double >, 0 > QuaternionMapd
Two-sided Jacobi SVD decomposition of a rectangular matrix.
Map< Quaternion< float >, Aligned > QuaternionMapAlignedf
const AutoDiffScalar< Matrix< typename internal::traits< typename internal::remove_all< DerTypeA >::type >::Scalar, Dynamic, 1 > > atan2(const AutoDiffScalar< DerTypeA > &a, const AutoDiffScalar< DerTypeB > &b)
EIGEN_DEVICE_FUNC Quaternion< Scalar > slerp(const Scalar &t, const QuaternionBase< OtherDerived > &other) const
EIGEN_DEVICE_FUNC const SinReturnType sin() const
EIGEN_DEVICE_FUNC Scalar x() const
EIGEN_DEVICE_FUNC Scalar & w()
internal::traits< Map >::Coefficients Coefficients
Matrix< Scalar, 3, 3 > Matrix3
EIGEN_DEVICE_FUNC Scalar & x()
static EIGEN_DEVICE_FUNC Quaternion UnitRandom()
void run(Expr &expr, Dev &dev)
EIGEN_DEVICE_FUNC Scalar y() const
EIGEN_DEVICE_FUNC const Scalar & b
internal::traits< Derived >::Scalar Scalar
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Vector3 _transformVector(const Vector3 &v) const
Base class for all dense matrices, vectors, and expressions.
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalar > run(const QuaternionBase< Derived1 > &a, const QuaternionBase< Derived2 > &b)
QuaternionBase< Quaternion< _Scalar, _Options > > Base
Quaternion< float > Quaternionf
Map< Quaternion< double >, Aligned > QuaternionMapAlignedd
EIGEN_DEVICE_FUNC Scalar squaredNorm() const
QuaternionBase< Map< Quaternion< _Scalar >, _Options > > Base
static EIGEN_DEVICE_FUNC void run(QuaternionBase< Derived > &q, const Other &a_mat)