Eigen/Eigen/src/Geometry/Quaternion.h
Go to the documentation of this file.
1 // This file is part of Eigen, a lightweight C++ template library
2 // for linear algebra.
3 //
4 // Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>
5 // Copyright (C) 2009 Mathieu Gautier <mathieu.gautier@cea.fr>
6 //
7 // This Source Code Form is subject to the terms of the Mozilla
8 // Public License v. 2.0. If a copy of the MPL was not distributed
9 // with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
10 
11 #ifndef EIGEN_QUATERNION_H
12 #define EIGEN_QUATERNION_H
13 // IWYU pragma: private
14 #include "./InternalHeaderCheck.h"
15 
16 namespace Eigen {
17 
18 /***************************************************************************
19  * Definition of QuaternionBase<Derived>
20  * The implementation is at the end of the file
21  ***************************************************************************/
22 
23 namespace internal {
24 template <typename Other, int OtherRows = Other::RowsAtCompileTime, int OtherCols = Other::ColsAtCompileTime>
26 }
27 
34 template <class Derived>
35 class QuaternionBase : public RotationBase<Derived, 3> {
36  public:
38 
39  using Base::operator*;
40  using Base::derived;
41 
45  typedef typename Coefficients::CoeffReturnType CoeffReturnType;
48 
50 
51  // typedef typename Matrix<Scalar,4,1> Coefficients;
58 
60  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline CoeffReturnType x() const { return this->derived().coeffs().coeff(0); }
62  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline CoeffReturnType y() const { return this->derived().coeffs().coeff(1); }
64  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline CoeffReturnType z() const { return this->derived().coeffs().coeff(2); }
66  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline CoeffReturnType w() const { return this->derived().coeffs().coeff(3); }
67 
69  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline NonConstCoeffReturnType x() { return this->derived().coeffs().x(); }
71  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline NonConstCoeffReturnType y() { return this->derived().coeffs().y(); }
73  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline NonConstCoeffReturnType z() { return this->derived().coeffs().z(); }
75  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline NonConstCoeffReturnType w() { return this->derived().coeffs().w(); }
76 
78  EIGEN_DEVICE_FUNC inline const VectorBlock<const Coefficients, 3> vec() const { return coeffs().template head<3>(); }
79 
81  EIGEN_DEVICE_FUNC inline VectorBlock<Coefficients, 3> vec() { return coeffs().template head<3>(); }
82 
85  return derived().coeffs();
86  }
87 
89  EIGEN_DEVICE_FUNC inline typename internal::traits<Derived>::Coefficients& coeffs() { return derived().coeffs(); }
90 
92  template <class OtherDerived>
94 
95  // disabled this copy operator as it is giving very strange compilation errors when compiling
96  // test_stdvector with GCC 4.4.2. This looks like a GCC bug though, so feel free to re-enable it if it's
97  // useful; however notice that we already have the templated operator= above and e.g. in MatrixBase
98  // we didn't have to add, in addition to templated operator=, such a non-templated copy operator.
99  // Derived& operator=(const QuaternionBase& other)
100  // { return operator=<Derived>(other); }
101 
103  template <class OtherDerived>
105 
110  return Quaternion<Scalar>(Scalar(1), Scalar(0), Scalar(0), Scalar(0));
111  }
112 
116  coeffs() << Scalar(0), Scalar(0), Scalar(0), Scalar(1);
117  return *this;
118  }
119 
123  EIGEN_DEVICE_FUNC inline Scalar squaredNorm() const { return coeffs().squaredNorm(); }
124 
128  EIGEN_DEVICE_FUNC inline Scalar norm() const { return coeffs().norm(); }
129 
132  EIGEN_DEVICE_FUNC inline void normalize() { coeffs().normalize(); }
136 
142  template <class OtherDerived>
144  return coeffs().dot(other.coeffs());
145  }
146 
147  template <class OtherDerived>
149 
152 
154  template <typename Derived1, typename Derived2>
156 
157  template <class OtherDerived>
159  template <class OtherDerived>
161 
164 
167 
168  template <class OtherDerived>
170 
175  template <class OtherDerived>
177  return coeffs() == other.coeffs();
178  }
179 
184  template <class OtherDerived>
186  return coeffs() != other.coeffs();
187  }
188 
193  template <class OtherDerived>
195  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const {
196  return coeffs().isApprox(other.coeffs(), prec);
197  }
198 
201 
202 #ifdef EIGEN_PARSED_BY_DOXYGEN
208  template <typename NewScalarType>
210 
211 #else
212 
213  template <typename NewScalarType>
215  const {
216  return derived();
217  }
218 
219  template <typename NewScalarType>
222  cast() const {
223  return Quaternion<NewScalarType>(coeffs().template cast<NewScalarType>());
224  }
225 #endif
226 
227 #ifndef EIGEN_NO_IO
228  friend std::ostream& operator<<(std::ostream& s, const QuaternionBase<Derived>& q) {
229  s << q.x() << "i + " << q.y() << "j + " << q.z() << "k"
230  << " + " << q.w();
231  return s;
232  }
233 #endif
234 
235 #ifdef EIGEN_QUATERNIONBASE_PLUGIN
236 #include EIGEN_QUATERNIONBASE_PLUGIN
237 #endif
238  protected:
241 };
242 
243 /***************************************************************************
244  * Definition/implementation of Quaternion<Scalar>
245  ***************************************************************************/
246 
274 namespace internal {
275 template <typename Scalar_, int Options_>
276 struct traits<Quaternion<Scalar_, Options_> > {
278  typedef Scalar_ Scalar;
281 };
282 } // namespace internal
283 
284 template <typename Scalar_, int Options_>
285 class Quaternion : public QuaternionBase<Quaternion<Scalar_, Options_> > {
286  public:
288  enum { NeedsAlignment = internal::traits<Quaternion>::Alignment > 0 };
289 
290  typedef Scalar_ Scalar;
291 
293  using Base::operator*=;
294 
297 
300 
308  EIGEN_DEVICE_FUNC inline Quaternion(const Scalar& w, const Scalar& x, const Scalar& y, const Scalar& z)
309  : m_coeffs(x, y, z, w) {}
310 
314  template <typename Derived>
316  : m_coeffs(vec.x(), vec.y(), vec.z(), w) {
318  }
319 
321  EIGEN_DEVICE_FUNC explicit inline Quaternion(const Scalar* data) : m_coeffs(data) {}
322 
324  template <class Derived>
326  this->Base::operator=(other);
327  }
328 
330  EIGEN_DEVICE_FUNC explicit inline Quaternion(const AngleAxisType& aa) { *this = aa; }
331 
336  template <typename Derived>
337  EIGEN_DEVICE_FUNC explicit inline Quaternion(const MatrixBase<Derived>& other) {
338  *this = other;
339  }
340 
342  template <typename OtherScalar, int OtherOptions>
344  m_coeffs = other.coeffs().template cast<Scalar>();
345  }
346 
347  // We define a copy constructor, which means we don't get an implicit move constructor or assignment operator.
351  : m_coeffs(std::move(other.coeffs())) {}
352 
356  m_coeffs = std::move(other.coeffs());
357  return *this;
358  }
359 
361 
362  template <typename Derived1, typename Derived2>
364 
366  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }
367 
368  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(bool(NeedsAlignment))
369 
370 #ifdef EIGEN_QUATERNION_PLUGIN
371 #include EIGEN_QUATERNION_PLUGIN
372 #endif
373 
374  protected:
376 
377 #ifndef EIGEN_PARSED_BY_DOXYGEN
378  EIGEN_STATIC_ASSERT((Options_ & DontAlign) == Options_, INVALID_MATRIX_TEMPLATE_PARAMETERS)
379 #endif
380 };
381 
388 
389 /***************************************************************************
390  * Specialization of Map<Quaternion<Scalar>>
391  ***************************************************************************/
392 
393 namespace internal {
394 template <typename Scalar_, int Options_>
395 struct traits<Map<Quaternion<Scalar_>, Options_> >
396  : traits<Quaternion<Scalar_, (int(Options_) & Aligned) == Aligned ? AutoAlign : DontAlign> > {
398 };
399 } // namespace internal
400 
401 namespace internal {
402 template <typename Scalar_, int Options_>
403 struct traits<Map<const Quaternion<Scalar_>, Options_> >
404  : traits<Quaternion<Scalar_, (int(Options_) & Aligned) == Aligned ? AutoAlign : DontAlign> > {
406  typedef traits<Quaternion<Scalar_, (int(Options_) & Aligned) == Aligned ? AutoAlign : DontAlign> > TraitsBase;
407  enum { Flags = TraitsBase::Flags & ~LvalueBit };
408 };
409 } // namespace internal
410 
422 template <typename Scalar_, int Options_>
423 class Map<const Quaternion<Scalar_>, Options_> : public QuaternionBase<Map<const Quaternion<Scalar_>, Options_> > {
424  public:
426 
427  typedef Scalar_ Scalar;
430  using Base::operator*=;
431 
438  EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE Map(const Scalar* coeffs) : m_coeffs(coeffs) {}
439 
440  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }
441 
442  protected:
444 };
445 
457 template <typename Scalar_, int Options_>
458 class Map<Quaternion<Scalar_>, Options_> : public QuaternionBase<Map<Quaternion<Scalar_>, Options_> > {
459  public:
461 
462  typedef Scalar_ Scalar;
465  using Base::operator*=;
466 
473  EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE Map(Scalar* coeffs) : m_coeffs(coeffs) {}
474 
475  EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs; }
476  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }
477 
478  protected:
480 };
481 
494 
495 /***************************************************************************
496  * Implementation of QuaternionBase methods
497  ***************************************************************************/
498 
499 // Generic Quaternion * Quaternion product
500 // This product can be specialized for a given architecture via the Arch template argument.
501 namespace internal {
502 template <int Arch, class Derived1, class Derived2, typename Scalar>
503 struct quat_product {
505  const QuaternionBase<Derived2>& b) {
506  return Quaternion<Scalar>(a.w() * b.w() - a.x() * b.x() - a.y() * b.y() - a.z() * b.z(),
507  a.w() * b.x() + a.x() * b.w() + a.y() * b.z() - a.z() * b.y(),
508  a.w() * b.y() + a.y() * b.w() + a.z() * b.x() - a.x() * b.z(),
509  a.w() * b.z() + a.z() * b.w() + a.x() * b.y() - a.y() * b.x());
510  }
511 };
512 } // namespace internal
513 
515 template <class Derived>
516 template <class OtherDerived>
521  YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
522  return internal::quat_product<Architecture::Target, Derived, OtherDerived,
523  typename internal::traits<Derived>::Scalar>::run(*this, other);
524 }
525 
527 template <class Derived>
528 template <class OtherDerived>
530  const QuaternionBase<OtherDerived>& other) {
531  derived() = derived() * other.derived();
532  return derived();
533 }
534 
542 template <class Derived>
545  // Note that this algorithm comes from the optimization by hand
546  // of the conversion to a Matrix followed by a Matrix/Vector product.
547  // It appears to be much faster than the common algorithm found
548  // in the literature (30 versus 39 flops). It also requires two
549  // Vector3 as temporaries.
550  Vector3 uv = this->vec().cross(v);
551  uv += uv;
552  return v + this->w() * uv + this->vec().cross(uv);
553 }
554 
555 template <class Derived>
557  const QuaternionBase<Derived>& other) {
558  coeffs() = other.coeffs();
559  return derived();
560 }
561 
562 template <class Derived>
563 template <class OtherDerived>
565  const QuaternionBase<OtherDerived>& other) {
566  coeffs() = other.coeffs();
567  return derived();
568 }
569 
572 template <class Derived>
576  Scalar ha = Scalar(0.5) * aa.angle(); // Scalar(0.5) to suppress precision loss warnings
577  this->w() = cos(ha);
578  this->vec() = sin(ha) * aa.axis();
579  return derived();
580 }
581 
588 template <class Derived>
589 template <class MatrixDerived>
593  YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
595  return derived();
596 }
597 
601 template <class Derived>
603  void) const {
604  // NOTE if inlined, then gcc 4.2 and 4.4 get rid of the temporary (not gcc 4.3 !!)
605  // if not inlined then the cost of the return by value is huge ~ +35%,
606  // however, not inlining this function is an order of magnitude slower, so
607  // it has to be inlined, and so the return by value is not an issue
608  Matrix3 res;
609 
610  const Scalar tx = Scalar(2) * this->x();
611  const Scalar ty = Scalar(2) * this->y();
612  const Scalar tz = Scalar(2) * this->z();
613  const Scalar twx = tx * this->w();
614  const Scalar twy = ty * this->w();
615  const Scalar twz = tz * this->w();
616  const Scalar txx = tx * this->x();
617  const Scalar txy = ty * this->x();
618  const Scalar txz = tz * this->x();
619  const Scalar tyy = ty * this->y();
620  const Scalar tyz = tz * this->y();
621  const Scalar tzz = tz * this->z();
622 
623  res.coeffRef(0, 0) = Scalar(1) - (tyy + tzz);
624  res.coeffRef(0, 1) = txy - twz;
625  res.coeffRef(0, 2) = txz + twy;
626  res.coeffRef(1, 0) = txy + twz;
627  res.coeffRef(1, 1) = Scalar(1) - (txx + tzz);
628  res.coeffRef(1, 2) = tyz - twx;
629  res.coeffRef(2, 0) = txz - twy;
630  res.coeffRef(2, 1) = tyz + twx;
631  res.coeffRef(2, 2) = Scalar(1) - (txx + tyy);
632 
633  return res;
634 }
635 
646 template <class Derived>
647 template <typename Derived1, typename Derived2>
649  const MatrixBase<Derived2>& b) {
651  Vector3 v0 = a.normalized();
652  Vector3 v1 = b.normalized();
653  Scalar c = v1.dot(v0);
654 
655  // if dot == -1, vectors are nearly opposites
656  // => accurately compute the rotation axis by computing the
657  // intersection of the two planes. This is done by solving:
658  // x^T v0 = 0
659  // x^T v1 = 0
660  // under the constraint:
661  // ||x|| = 1
662  // which yields a singular value problem
664  c = numext::maxi(c, Scalar(-1));
666  m << v0.transpose(), v1.transpose();
668  Vector3 axis = svd.matrixV().col(2);
669 
670  Scalar w2 = (Scalar(1) + c) * Scalar(0.5);
671  this->w() = sqrt(w2);
672  this->vec() = axis * sqrt(Scalar(1) - w2);
673  return derived();
674  }
675  Vector3 axis = v0.cross(v1);
676  Scalar s = sqrt((Scalar(1) + c) * Scalar(2));
677  Scalar invs = Scalar(1) / s;
678  this->vec() = axis * invs;
679  this->w() = s * Scalar(0.5);
680 
681  return derived();
682 }
683 
688 template <typename Scalar, int Options>
693  const Scalar u1 = internal::random<Scalar>(0, 1), u2 = internal::random<Scalar>(0, 2 * EIGEN_PI),
694  u3 = internal::random<Scalar>(0, 2 * EIGEN_PI);
695  const Scalar a = sqrt(Scalar(1) - u1), b = sqrt(u1);
696  return Quaternion(a * sin(u2), a * cos(u2), b * sin(u3), b * cos(u3));
697 }
698 
709 template <typename Scalar, int Options>
710 template <typename Derived1, typename Derived2>
712  const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b) {
713  Quaternion quat;
714  quat.setFromTwoVectors(a, b);
715  return quat;
716 }
717 
724 template <class Derived>
726  const {
727  // FIXME should this function be called multiplicativeInverse and conjugate() be called inverse() or opposite() ??
728  Scalar n2 = this->squaredNorm();
729  if (n2 > Scalar(0))
730  return Quaternion<Scalar>(conjugate().coeffs() / n2);
731  else {
732  // return an invalid result to flag the error
734  }
735 }
736 
737 // Generic conjugate of a Quaternion
738 namespace internal {
739 template <int Arch, class Derived, typename Scalar>
740 struct quat_conj {
742  return Quaternion<Scalar>(q.w(), -q.x(), -q.y(), -q.z());
743  }
744 };
745 } // namespace internal
746 
753 template <class Derived>
755  const {
757 }
758 
762 template <class Derived>
763 template <class OtherDerived>
765  const QuaternionBase<OtherDerived>& other) const {
767  Quaternion<Scalar> d = (*this) * other.conjugate();
768  return Scalar(2) * atan2(d.vec().norm(), numext::abs(d.w()));
769 }
770 
777 template <class Derived>
778 template <class OtherDerived>
780  const Scalar& t, const QuaternionBase<OtherDerived>& other) const {
783  const Scalar one = Scalar(1) - NumTraits<Scalar>::epsilon();
784  Scalar d = this->dot(other);
785  Scalar absD = numext::abs(d);
786 
787  Scalar scale0;
788  Scalar scale1;
789 
790  if (absD >= one) {
791  scale0 = Scalar(1) - t;
792  scale1 = t;
793  } else {
794  // theta is the angle between the 2 quaternions
795  Scalar theta = acos(absD);
796  Scalar sinTheta = sin(theta);
797 
798  scale0 = sin((Scalar(1) - t) * theta) / sinTheta;
799  scale1 = sin((t * theta)) / sinTheta;
800  }
801  if (d < Scalar(0)) scale1 = -scale1;
802 
803  return Quaternion<Scalar>(scale0 * coeffs() + scale1 * other.coeffs());
804 }
805 
806 namespace internal {
807 
808 // set from a rotation matrix
809 template <typename Other>
810 struct quaternionbase_assign_impl<Other, 3, 3> {
811  typedef typename Other::Scalar Scalar;
812  template <class Derived>
813  EIGEN_DEVICE_FUNC static inline void run(QuaternionBase<Derived>& q, const Other& a_mat) {
814  const typename internal::nested_eval<Other, 2>::type mat(a_mat);
816  // This algorithm comes from "Quaternion Calculus and Fast Animation",
817  // Ken Shoemake, 1987 SIGGRAPH course notes
818  Scalar t = mat.trace();
819  if (t > Scalar(0)) {
820  t = sqrt(t + Scalar(1.0));
821  q.w() = Scalar(0.5) * t;
822  t = Scalar(0.5) / t;
823  q.x() = (mat.coeff(2, 1) - mat.coeff(1, 2)) * t;
824  q.y() = (mat.coeff(0, 2) - mat.coeff(2, 0)) * t;
825  q.z() = (mat.coeff(1, 0) - mat.coeff(0, 1)) * t;
826  } else {
827  Index i = 0;
828  if (mat.coeff(1, 1) > mat.coeff(0, 0)) i = 1;
829  if (mat.coeff(2, 2) > mat.coeff(i, i)) i = 2;
830  Index j = (i + 1) % 3;
831  Index k = (j + 1) % 3;
832 
833  t = sqrt(mat.coeff(i, i) - mat.coeff(j, j) - mat.coeff(k, k) + Scalar(1.0));
834  q.coeffs().coeffRef(i) = Scalar(0.5) * t;
835  t = Scalar(0.5) / t;
836  q.w() = (mat.coeff(k, j) - mat.coeff(j, k)) * t;
837  q.coeffs().coeffRef(j) = (mat.coeff(j, i) + mat.coeff(i, j)) * t;
838  q.coeffs().coeffRef(k) = (mat.coeff(k, i) + mat.coeff(i, k)) * t;
839  }
840  }
841 };
842 
843 // set from a vector of coefficients assumed to be a quaternion
844 template <typename Other>
845 struct quaternionbase_assign_impl<Other, 4, 1> {
846  typedef typename Other::Scalar Scalar;
847  template <class Derived>
848  EIGEN_DEVICE_FUNC static inline void run(QuaternionBase<Derived>& q, const Other& vec) {
849  q.coeffs() = vec;
850  }
851 };
852 
853 } // end namespace internal
854 
855 } // end namespace Eigen
856 
857 #endif // EIGEN_QUATERNION_H
AnnoyingScalar cos(const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:136
AnnoyingScalar acos(const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:138
AnnoyingScalar sin(const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:137
AnnoyingScalar sqrt(const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:134
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Eigen::SparseMatrix< double > mat
Definition: EigenUnitTest.cpp:10
cout<< "Here is the matrix m:"<< endl<< m<< endl;JacobiSVD< MatrixXf, ComputeThinU|ComputeThinV > svd(m)
#define EIGEN_DEFAULT_COPY_CONSTRUCTOR(CLASS)
Macro to explicitly define the default copy constructor. This is necessary, because the implicit defi...
Definition: Macros.h:1119
#define EIGEN_NOEXCEPT_IF(x)
Definition: Macros.h:1268
#define EIGEN_USING_STD(FUNC)
Definition: Macros.h:1090
#define EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(Derived)
Macro to manually define default constructors and destructors. This is necessary when the copy constr...
Definition: Macros.h:1137
#define EIGEN_CONSTEXPR
Definition: Macros.h:758
#define EIGEN_DEVICE_FUNC
Definition: Macros.h:892
#define EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Derived)
Macro to manually inherit assignment operators. This is necessary, because the implicitly defined ass...
Definition: Macros.h:1126
#define EIGEN_STRONG_INLINE
Definition: Macros.h:834
int data[]
Definition: Map_placement_new.cpp:1
#define EIGEN_PI
Definition: MathFunctions.h:16
RowVector3d w
Definition: Matrix_resize_int.cpp:3
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
Definition: Memory.h:876
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Definition: PartialRedux_count.cpp:3
#define EIGEN_STATIC_ASSERT(X, MSG)
Definition: StaticAssert.h:26
#define EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(TYPE, SIZE)
Definition: StaticAssert.h:50
M1<< 1, 2, 3, 4, 5, 6, 7, 8, 9;Map< RowVectorXf > v1(M1.data(), M1.size())
Scalar * b
Definition: benchVecAdd.cpp:17
SCALAR Scalar
Definition: bench_gemm.cpp:45
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
Definition: AngleAxis.h:52
EIGEN_DEVICE_FUNC const Vector3 & axis() const
Definition: AngleAxis.h:99
EIGEN_DEVICE_FUNC Scalar angle() const
Definition: AngleAxis.h:94
Two-sided Jacobi SVD decomposition of a rectangular matrix.
Definition: JacobiSVD.h:500
Coefficients m_coeffs
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:479
internal::traits< Map >::Coefficients Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:463
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Map(Scalar *coeffs)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:473
EIGEN_DEVICE_FUNC const Coefficients & coeffs() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:476
Scalar_ Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:462
QuaternionBase< Map< Quaternion< Scalar_ >, Options_ > > Base
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:460
EIGEN_DEVICE_FUNC Coefficients & coeffs()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:475
EIGEN_DEVICE_FUNC const Coefficients & coeffs() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:440
QuaternionBase< Map< const Quaternion< Scalar_ >, Options_ > > Base
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:425
Scalar_ Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:427
internal::traits< Map >::Coefficients Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:428
const Coefficients m_coeffs
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:443
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Map(const Scalar *coeffs)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:438
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:96
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:52
Base class for quaternion expressions.
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:35
EIGEN_DEVICE_FUNC Scalar angularDistance(const QuaternionBase< OtherDerived > &other) const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Vector3 _transformVector(const Vector3 &v) const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:544
Matrix< Scalar, 3, 3 > Matrix3
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:55
EIGEN_DEVICE_FUNC Quaternion< Scalar > slerp(const Scalar &t, const QuaternionBase< OtherDerived > &other) const
EIGEN_DEVICE_FUNC bool operator!=(const QuaternionBase< OtherDerived > &other) const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:185
EIGEN_DEVICE_FUNC QuaternionBase & setIdentity()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:115
Matrix< Scalar, 3, 1 > Vector3
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:53
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR NonConstCoeffReturnType y()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:71
friend std::ostream & operator<<(std::ostream &s, const QuaternionBase< Derived > &q)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:228
static EIGEN_DEVICE_FUNC Quaternion< Scalar > Identity()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:109
EIGEN_DEVICE_FUNC Scalar norm() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:128
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR CoeffReturnType w() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:66
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase< Derived > & operator=(const QuaternionBase< Derived > &other)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:556
EIGEN_DEVICE_FUNC std::enable_if_t<!internal::is_same< Scalar, NewScalarType >::value, Quaternion< NewScalarType > > cast() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:222
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR NonConstCoeffReturnType z()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:73
EIGEN_DEVICE_FUNC Scalar squaredNorm() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:123
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR CoeffReturnType z() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:64
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR NonConstCoeffReturnType w()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:75
EIGEN_DEVICE_FUNC Derived & setFromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:648
EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:602
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalar > operator*(const QuaternionBase< OtherDerived > &q) const
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:725
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & operator=(const QuaternionBase< OtherDerived > &other)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:564
EIGEN_DEVICE_FUNC Derived & operator=(const MatrixBase< OtherDerived > &m)
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR CoeffReturnType x() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:60
EIGEN_DEVICE_FUNC bool isApprox(const QuaternionBase< OtherDerived > &other, const RealScalar &prec=NumTraits< Scalar >::dummy_precision()) const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:194
EIGEN_DEVICE_FUNC const VectorBlock< const Coefficients, 3 > vec() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:78
EIGEN_DEVICE_FUNC const internal::traits< Derived >::Coefficients & coeffs() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:84
EIGEN_DEVICE_FUNC Quaternion< Scalar > conjugate() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:754
EIGEN_DEVICE_FUNC void normalize()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:132
EIGEN_DEVICE_FUNC Scalar dot(const QuaternionBase< OtherDerived > &other) const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:143
EIGEN_DEVICE_FUNC std::enable_if_t< internal::is_same< Scalar, NewScalarType >::value, const Derived & > cast() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:214
std::conditional_t< bool(internal::traits< Derived >::Flags &LvalueBit), Scalar &, CoeffReturnType > NonConstCoeffReturnType
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:47
internal::traits< Derived >::Coefficients Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:44
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR CoeffReturnType y() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:62
RotationBase< Derived, 3 > Base
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:37
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR NonConstCoeffReturnType x()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:69
EIGEN_DEVICE_FUNC VectorBlock< Coefficients, 3 > vec()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:81
Coefficients::CoeffReturnType CoeffReturnType
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:45
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & operator*=(const QuaternionBase< OtherDerived > &q)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:529
EIGEN_DEVICE_FUNC bool operator==(const QuaternionBase< OtherDerived > &other) const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:176
NumTraits< Scalar >::Real RealScalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:43
internal::traits< Derived >::Scalar Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:42
AngleAxis< Scalar > AngleAxisType
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:57
EIGEN_DEVICE_FUNC Quaternion< Scalar > normalized() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:135
EIGEN_DEVICE_FUNC Derived & operator=(const AngleAxisType &aa)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:573
EIGEN_DEVICE_FUNC internal::traits< Derived >::Coefficients & coeffs()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:89
The quaternion class used to represent 3D orientations and rotations.
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:285
static EIGEN_DEVICE_FUNC Quaternion FromTwoVectors(const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
EIGEN_DEVICE_FUNC Quaternion(const Scalar &w, const Eigen::MatrixBase< Derived > &vec)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:315
Base::AngleAxisType AngleAxisType
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:296
EIGEN_DEVICE_FUNC Quaternion(const Quaternion< OtherScalar, OtherOptions > &other)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:343
EIGEN_DEVICE_FUNC Quaternion(const Scalar *data)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:321
QuaternionBase< Quaternion< Scalar_, Options_ > > Base
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:287
Coefficients m_coeffs
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:375
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion(const QuaternionBase< Derived > &other)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:325
EIGEN_DEVICE_FUNC Coefficients & coeffs()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:365
internal::traits< Quaternion >::Coefficients Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:295
EIGEN_DEVICE_FUNC Quaternion(const Scalar &w, const Scalar &x, const Scalar &y, const Scalar &z)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:308
EIGEN_DEVICE_FUNC Quaternion(Quaternion &&other) EIGEN_NOEXCEPT_IF(std
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:349
EIGEN_DEVICE_FUNC Quaternion & operator=(Quaternion &&other) EIGEN_NOEXCEPT_IF(std
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:354
EIGEN_DEVICE_FUNC const Coefficients & coeffs() const
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:366
EIGEN_DEVICE_FUNC Quaternion()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:299
EIGEN_DEVICE_FUNC Quaternion(const AngleAxisType &aa)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:330
Scalar_ Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:290
EIGEN_DEVICE_FUNC Quaternion(const MatrixBase< Derived > &other)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:337
static EIGEN_DEVICE_FUNC Quaternion UnitRandom()
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:689
Common base class for compact rotation representations.
Definition: RotationBase.h:32
EIGEN_DEVICE_FUNC const Derived & derived() const
Definition: RotationBase.h:43
Scalar coeff(Index row, Index col) const
Definition: SparseMatrix.h:211
Expression of a fixed-size or dynamic-size sub-vector.
Definition: VectorBlock.h:58
Map< Quaternion< double >, Aligned > QuaternionMapAlignedd
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:493
Quaternion< double > Quaterniond
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:387
Quaternion< float > Quaternionf
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:384
Map< Quaternion< float >, 0 > QuaternionMapf
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:484
Map< Quaternion< double >, 0 > QuaternionMapd
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:487
Map< Quaternion< float >, Aligned > QuaternionMapAlignedf
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:490
@ Aligned
Definition: Constants.h:242
@ DontAlign
Definition: Constants.h:324
@ AutoAlign
Definition: Constants.h:322
@ ComputeFullV
Definition: Constants.h:393
const unsigned int LvalueBit
Definition: Constants.h:148
Scalar * y
Definition: level1_cplx_impl.h:128
RealScalar s
Definition: level1_cplx_impl.h:130
return int(ret)+1
Scalar EIGEN_BLAS_FUNC_NAME() dot(int *n, Scalar *px, int *incx, Scalar *py, int *incy)
Definition: level1_real_impl.h:52
const Scalar * a
Definition: level2_cplx_impl.h:32
int * m
Definition: level2_cplx_impl.h:294
char char char int int * k
Definition: level2_impl.h:374
double theta
Definition: two_d_biharmonic.cc:236
@ Target
Definition: Constants.h:495
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE T maxi(const T &x, const T &y)
Definition: MathFunctions.h:926
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE std::enable_if_t< NumTraits< T >::IsSigned||NumTraits< T >::IsComplex, typename NumTraits< T >::Real > abs(const T &x)
Definition: MathFunctions.h:1355
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:2019
Namespace containing all symbols from the Eigen library.
Definition: bench_norm.cpp:70
auto run(Kernel kernel, Args &&... args) -> decltype(kernel(args...))
Definition: gpu_test_helper.h:414
AutoDiffScalar< Matrix< typename internal::traits< internal::remove_all_t< DerTypeA > >::Scalar, Dynamic, 1 > > atan2(const AutoDiffScalar< DerTypeA > &a, const AutoDiffScalar< DerTypeB > &b)
Definition: AutoDiffScalar.h:558
squared absolute value
Definition: GlobalFunctions.h:87
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:83
Extend namespace for flags.
Definition: fsi_chan_precond_driver.cc:56
int c
Definition: calibrate.py:100
type
Definition: compute_granudrum_aor.py:141
Definition: Eigen_Colamd.h:49
double Zero
Definition: pseudosolid_node_update_elements.cc:35
double epsilon
Definition: osc_ring_sarah_asymptotics.h:43
list x
Definition: plotDoE.py:28
t
Definition: plotPSD.py:36
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
Definition: NumTraits.h:217
Definition: XprHelper.h:583
Definition: Meta.h:205
std::conditional_t< Evaluate, PlainObject, typename ref_selector< T >::type > type
Definition: XprHelper.h:549
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:740
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalar > run(const QuaternionBase< Derived > &q)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:741
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:503
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalar > run(const QuaternionBase< Derived1 > &a, const QuaternionBase< Derived2 > &b)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:504
static EIGEN_DEVICE_FUNC void run(QuaternionBase< Derived > &q, const Other &a_mat)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:813
Other::Scalar Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:811
static EIGEN_DEVICE_FUNC void run(QuaternionBase< Derived > &q, const Other &vec)
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:848
Other::Scalar Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:846
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:25
Map< Matrix< Scalar_, 4, 1 >, Options_ > Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:397
Map< const Matrix< Scalar_, 4, 1 >, Options_ > Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:405
Scalar_ Scalar
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:278
Matrix< Scalar_, 4, 1, Options_ > Coefficients
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:279
Quaternion< Scalar_, Options_ > PlainObject
Definition: Eigen/Eigen/src/Geometry/Quaternion.h:277
Definition: ForwardDeclarations.h:21
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
void run(const string &dir_name, LinearSolver *linear_solver_pt, const unsigned nel_1d, bool mess_up_order)
Definition: two_d_poisson_compare_solvers.cc:317