Public Types | Public Member Functions | Static Public Member Functions | Friends | List of all members
Eigen::QuaternionBase Class Reference

Base class for quaternion expressions. More...

#include <ForwardDeclarations.h>

Public Types

enum  { Flags = Eigen::internal::traits<Derived>::Flags }
 
typedef AngleAxis< ScalarAngleAxisType
 
typedef RotationBase< Derived, 3 > Base
 
typedef internal::traits< Derived >::Coefficients Coefficients
 
typedef Coefficients::CoeffReturnType CoeffReturnType
 
typedef Matrix< Scalar, 3, 3 > Matrix3
 
typedef internal::conditional< bool(internal::traits< Derived >::Flags &LvalueBit), Scalar &, CoeffReturnType >::type NonConstCoeffReturnType
 
typedef NumTraits< Scalar >::Real RealScalar
 
typedef internal::traits< Derived >::Scalar Scalar
 
typedef Matrix< Scalar, 3, 1 > Vector3
 

Public Member Functions

EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Vector3 _transformVector (const Vector3 &v) const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC Scalar angularDistance (const QuaternionBase< OtherDerived > &other) const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC internal::traits< Derived >::Scalar angularDistance (const QuaternionBase< OtherDerived > &other) const
 
template<typename NewScalarType >
EIGEN_DEVICE_FUNC internal::enable_if< internal::is_same< Scalar, NewScalarType >::value, const Derived & >::type cast () const
 
template<typename NewScalarType >
EIGEN_DEVICE_FUNC internal::enable_if<!internal::is_same< Scalar, NewScalarType >::value, Quaternion< NewScalarType > >::type cast () const
 
EIGEN_DEVICE_FUNC internal::traits< Derived >::Coefficientscoeffs ()
 
const EIGEN_DEVICE_FUNC internal::traits< Derived >::Coefficientscoeffs () const
 
EIGEN_DEVICE_FUNC Quaternion< Scalarconjugate () const
 
EIGEN_DEVICE_FUNC Derived & derived ()
 
const EIGEN_DEVICE_FUNC Derived & derived () const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC Scalar dot (const QuaternionBase< OtherDerived > &other) const
 
EIGEN_DEVICE_FUNC Quaternion< Scalarinverse () const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC bool isApprox (const QuaternionBase< OtherDerived > &other, const RealScalar &prec=NumTraits< Scalar >::dummy_precision()) const
 
EIGEN_DEVICE_FUNC Scalar norm () const
 
EIGEN_DEVICE_FUNC void normalize ()
 
EIGEN_DEVICE_FUNC Quaternion< Scalarnormalized () const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC bool operator!= (const QuaternionBase< OtherDerived > &other) const
 
template<typename OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE internal::rotation_base_generic_product_selector< Derived, OtherDerived, OtherDerived::IsVectorAtCompileTime >::ReturnType operator* (const EigenBase< OtherDerived > &e) const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< typename internal::traits< Derived >::Scalaroperator* (const QuaternionBase< OtherDerived > &other) const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion< Scalaroperator* (const QuaternionBase< OtherDerived > &q) const
 
template<int Mode, int Options>
EIGEN_DEVICE_FUNC Transform< Scalar, Dim, Mode > operator* (const Transform< Scalar, Dim, Mode, Options > &t) const
 
EIGEN_DEVICE_FUNC Transform< Scalar, Dim, Isometryoperator* (const Translation< Scalar, Dim > &t) const
 
EIGEN_DEVICE_FUNC RotationMatrixType operator* (const UniformScaling< Scalar > &s) const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & operator*= (const QuaternionBase< OtherDerived > &q)
 
EIGEN_DEVICE_FUNC Derived & operator= (const AngleAxisType &aa)
 
template<class Derived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & operator= (const AngleAxisType &aa)
 
template<class MatrixDerived >
EIGEN_DEVICE_FUNC Derived & operator= (const MatrixBase< MatrixDerived > &xpr)
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC Derived & operator= (const MatrixBase< OtherDerived > &m)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase< Derived > & operator= (const QuaternionBase< Derived > &other)
 
template<class Derived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase< Derived > & operator= (const QuaternionBase< Derived > &other)
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & operator= (const QuaternionBase< OtherDerived > &other)
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC bool operator== (const QuaternionBase< OtherDerived > &other) const
 
template<typename Derived1 , typename Derived2 >
EIGEN_DEVICE_FUNC Derived & setFromTwoVectors (const MatrixBase< Derived1 > &a, const MatrixBase< Derived2 > &b)
 
EIGEN_DEVICE_FUNC QuaternionBasesetIdentity ()
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC Quaternion< Scalarslerp (const Scalar &t, const QuaternionBase< OtherDerived > &other) const
 
template<class OtherDerived >
EIGEN_DEVICE_FUNC Quaternion< typename internal::traits< Derived >::Scalarslerp (const Scalar &t, const QuaternionBase< OtherDerived > &other) const
 
EIGEN_DEVICE_FUNC Scalar squaredNorm () const
 
EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix () const
 
EIGEN_DEVICE_FUNC VectorBlock< Coefficients, 3 > vec ()
 
const EIGEN_DEVICE_FUNC VectorBlock< const Coefficients, 3 > vec () const
 
EIGEN_DEVICE_FUNC NonConstCoeffReturnType w ()
 
EIGEN_DEVICE_FUNC CoeffReturnType w () const
 
EIGEN_DEVICE_FUNC NonConstCoeffReturnType x ()
 
EIGEN_DEVICE_FUNC CoeffReturnType x () const
 
EIGEN_DEVICE_FUNC NonConstCoeffReturnType y ()
 
EIGEN_DEVICE_FUNC CoeffReturnType y () const
 
EIGEN_DEVICE_FUNC NonConstCoeffReturnType z ()
 
EIGEN_DEVICE_FUNC CoeffReturnType z () const
 

Static Public Member Functions

static EIGEN_DEVICE_FUNC Quaternion< ScalarIdentity ()
 

Friends

EIGEN_DEVICE_FUNC friend Transform< Scalar, Dim, Affineoperator* (const DiagonalMatrix< Scalar, Dim > &l, const Derived &r)
 
template<typename OtherDerived >
EIGEN_DEVICE_FUNC RotationMatrixType operator* (const EigenBase< OtherDerived > &l, const Derived &r)
 
std::ostream & operator<< (std::ostream &s, const QuaternionBase< Derived > &q)
 

Detailed Description

Base class for quaternion expressions.

\geometry_module

Template Parameters
Derivedderived type (CRTP)
See also
class Quaternion

Definition at line 288 of file ForwardDeclarations.h.

Member Typedef Documentation

◆ AngleAxisType

the equivalent angle-axis type

Definition at line 61 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ Base

◆ Coefficients

◆ CoeffReturnType

typedef Coefficients::CoeffReturnType Eigen::QuaternionBase::CoeffReturnType

◆ Matrix3

the equivalent rotation matrix type

Definition at line 59 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ NonConstCoeffReturnType

◆ RealScalar

◆ Scalar

◆ Vector3

the type of a 3D vector

Definition at line 57 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
Flags 

Definition at line 51 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

Member Function Documentation

◆ _transformVector()

EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase< Derived >::Vector3 Eigen::QuaternionBase::_transformVector ( const Vector3 v) const

return the result vector of v through the rotation

Rotation of a vector by a quaternion.

Remarks
If the quaternion is used to rotate several points (>1) then it is much more efficient to first convert it to a 3x3 Matrix. Comparison of the operation cost for n transformations:
  • Quaternion2: 30n
  • Via a Matrix3: 24 + 15n

Definition at line 531 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ angularDistance() [1/2]

template<class OtherDerived >
EIGEN_DEVICE_FUNC Scalar Eigen::QuaternionBase::angularDistance ( const QuaternionBase< OtherDerived > &  other) const

◆ angularDistance() [2/2]

template<class OtherDerived >
EIGEN_DEVICE_FUNC internal::traits<Derived>::Scalar Eigen::QuaternionBase::angularDistance ( const QuaternionBase< OtherDerived > &  other) const
inline
Returns
the angle (in radian) between two rotations
See also
dot()

Definition at line 764 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ cast() [1/2]

template<typename NewScalarType >
EIGEN_DEVICE_FUNC internal::enable_if<internal::is_same<Scalar,NewScalarType>::value,const Derived&>::type Eigen::QuaternionBase::cast ( ) const
inline

◆ cast() [2/2]

template<typename NewScalarType >
EIGEN_DEVICE_FUNC internal::enable_if<!internal::is_same<Scalar,NewScalarType>::value,Quaternion<NewScalarType> >::type Eigen::QuaternionBase::cast ( ) const
inline

◆ coeffs() [1/2]

EIGEN_DEVICE_FUNC internal::traits<Derived>::Coefficients& Eigen::QuaternionBase::coeffs ( )
inline
Returns
a vector expression of the coefficients (x,y,z,w)

Definition at line 93 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ coeffs() [2/2]

const EIGEN_DEVICE_FUNC internal::traits<Derived>::Coefficients& Eigen::QuaternionBase::coeffs ( ) const
inline
Returns
a read-only vector expression of the coefficients (x,y,z,w)

Definition at line 90 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ conjugate()

EIGEN_DEVICE_FUNC Quaternion< typename internal::traits< Derived >::Scalar > Eigen::QuaternionBase::conjugate ( ) const
inline
Returns
the conjugated quaternion
the conjugate of the *this which is equal to the multiplicative inverse if the quaternion is normalized. The conjugate of a quaternion represents the opposite rotation.
See also
Quaternion2::inverse()

Definition at line 751 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ derived() [1/2]

EIGEN_DEVICE_FUNC Derived& Eigen::RotationBase::derived
inline

Definition at line 42 of file RotationBase.h.

◆ derived() [2/2]

const EIGEN_DEVICE_FUNC Derived& Eigen::RotationBase::derived
inline

Definition at line 41 of file RotationBase.h.

◆ dot()

template<class OtherDerived >
EIGEN_DEVICE_FUNC Scalar Eigen::QuaternionBase::dot ( const QuaternionBase< OtherDerived > &  other) const
inline
Returns
the dot product of *this and other Geometrically speaking, the dot product of two unit quaternions corresponds to the cosine of half the angle between the two rotations.
See also
angularDistance()

Definition at line 139 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ Identity()

static EIGEN_DEVICE_FUNC Quaternion<Scalar> Eigen::QuaternionBase::Identity ( )
inlinestatic
Returns
a quaternion representing an identity rotation
See also
MatrixBase::Identity()

Definition at line 111 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ inverse()

EIGEN_DEVICE_FUNC Quaternion< typename internal::traits< Derived >::Scalar > Eigen::QuaternionBase::inverse ( ) const
inline
Returns
the quaternion describing the inverse rotation
the multiplicative inverse of *this Note that in most cases, i.e., if you simply want the opposite rotation, and/or the quaternion is normalized, then it is enough to use the conjugate.
See also
QuaternionBase::conjugate()

Definition at line 720 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ isApprox()

template<class OtherDerived >
EIGEN_DEVICE_FUNC bool Eigen::QuaternionBase::isApprox ( const QuaternionBase< OtherDerived > &  other,
const RealScalar prec = NumTraits<Scalar>::dummy_precision() 
) const
inline
Returns
true if *this is approximately equal to other, within the precision determined by prec.
See also
MatrixBase::isApprox()

Definition at line 182 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ norm()

EIGEN_DEVICE_FUNC Scalar Eigen::QuaternionBase::norm ( ) const
inline
Returns
the norm of the quaternion's coefficients
See also
QuaternionBase::squaredNorm(), MatrixBase::norm()

Definition at line 125 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ normalize()

EIGEN_DEVICE_FUNC void Eigen::QuaternionBase::normalize ( )
inline

Normalizes the quaternion *this

See also
normalized(), MatrixBase::normalize()

Definition at line 129 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ normalized()

EIGEN_DEVICE_FUNC Quaternion<Scalar> Eigen::QuaternionBase::normalized ( ) const
inline
Returns
a normalized copy of *this
See also
normalize(), MatrixBase::normalized()

Definition at line 132 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ operator!=()

template<class OtherDerived >
EIGEN_DEVICE_FUNC bool Eigen::QuaternionBase::operator!= ( const QuaternionBase< OtherDerived > &  other) const
inline
Returns
true if at least one pair of coefficients of *this and other are not exactly equal to each other.
Warning
When using floating point scalar values you probably should rather use a fuzzy comparison such as isApprox()
See also
isApprox(), operator==

Definition at line 174 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ operator*() [1/6]

template<typename OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE internal::rotation_base_generic_product_selector<Derived,OtherDerived,OtherDerived::IsVectorAtCompileTime>::ReturnType Eigen::RotationBase::operator* ( typename OtherDerived  )
inline
Returns
the concatenation of the rotation *this with a generic expression e e can be:
  • a DimxDim linear transformation matrix
  • a DimxDim diagonal matrix (axis aligned scaling)
  • a vector of size Dim

Definition at line 71 of file RotationBase.h.

◆ operator*() [2/6]

template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion<typename internal::traits<Derived>::Scalar> Eigen::QuaternionBase::operator* ( const QuaternionBase< OtherDerived > &  other) const
Returns
the concatenation of two rotations as a quaternion-quaternion product

Definition at line 505 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ operator*() [3/6]

template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion<Scalar> Eigen::QuaternionBase::operator* ( const QuaternionBase< OtherDerived > &  q) const

◆ operator*() [4/6]

template<int Mode, int Options>
EIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode> Eigen::RotationBase::operator* ( int  Mode,
int  Options 
)
inline
Returns
the concatenation of the rotation *this with a transformation t

Definition at line 89 of file RotationBase.h.

◆ operator*() [5/6]

EIGEN_DEVICE_FUNC Transform<Scalar,Dim,Isometry> Eigen::RotationBase::operator*
inline
Returns
the concatenation of the rotation *this with a translation t

Definition at line 56 of file RotationBase.h.

◆ operator*() [6/6]

EIGEN_DEVICE_FUNC RotationMatrixType Eigen::RotationBase::operator*
inline
Returns
the concatenation of the rotation *this with a uniform scaling s

Definition at line 60 of file RotationBase.h.

◆ operator*=()

template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & Eigen::QuaternionBase::operator*= ( const QuaternionBase< OtherDerived > &  other)
See also
operator*(Quaternion)

Definition at line 516 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ operator=() [1/7]

EIGEN_DEVICE_FUNC Derived& Eigen::QuaternionBase::operator= ( const AngleAxisType aa)

◆ operator=() [2/7]

template<class Derived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& Eigen::QuaternionBase::operator= ( const AngleAxisType aa)

Set *this from an angle-axis aa and returns a reference to *this

Definition at line 561 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ operator=() [3/7]

template<class MatrixDerived >
EIGEN_DEVICE_FUNC Derived& Eigen::QuaternionBase::operator= ( const MatrixBase< MatrixDerived > &  xpr)
inline

Set *this from the expression xpr:

  • if xpr is a 4x1 vector, then xpr is assumed to be a quaternion
  • if xpr is a 3x3 matrix, then xpr is assumed to be rotation matrix and xpr is converted to a quaternion

Definition at line 579 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ operator=() [4/7]

template<class OtherDerived >
EIGEN_DEVICE_FUNC Derived& Eigen::QuaternionBase::operator= ( const MatrixBase< OtherDerived > &  m)

◆ operator=() [5/7]

EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase<Derived>& Eigen::QuaternionBase::operator= ( const QuaternionBase< Derived > &  other)

◆ operator=() [6/7]

template<class Derived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase<Derived>& Eigen::QuaternionBase::operator= ( const QuaternionBase< Derived > &  other)

◆ operator=() [7/7]

template<class OtherDerived >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & Eigen::QuaternionBase::operator= ( const QuaternionBase< OtherDerived > &  other)

◆ operator==()

template<class OtherDerived >
EIGEN_DEVICE_FUNC bool Eigen::QuaternionBase::operator== ( const QuaternionBase< OtherDerived > &  other) const
inline
Returns
true if each coefficients of *this and other are all exactly equal.
Warning
When using floating point scalar values you probably should rather use a fuzzy comparison such as isApprox()
See also
isApprox(), operator!=

Definition at line 166 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ setFromTwoVectors()

template<typename Derived1 , typename Derived2 >
EIGEN_DEVICE_FUNC Derived & Eigen::QuaternionBase::setFromTwoVectors ( const MatrixBase< Derived1 > &  a,
const MatrixBase< Derived2 > &  b 
)
inline
Returns
the quaternion which transform a into b through a rotation

Sets *this to be a quaternion representing a rotation between the two arbitrary vectors a and b. In other words, the built rotation represent a rotation sending the line of direction a to the line of direction b, both lines passing through the origin.

Returns
a reference to *this.

Note that the two input vectors do not have to be normalized, and do not need to have the same norm.

Definition at line 638 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ setIdentity()

EIGEN_DEVICE_FUNC QuaternionBase& Eigen::QuaternionBase::setIdentity ( )
inline

◆ slerp() [1/2]

template<class OtherDerived >
EIGEN_DEVICE_FUNC Quaternion<Scalar> Eigen::QuaternionBase::slerp ( const Scalar t,
const QuaternionBase< OtherDerived > &  other 
) const

◆ slerp() [2/2]

template<class OtherDerived >
EIGEN_DEVICE_FUNC Quaternion<typename internal::traits<Derived>::Scalar> Eigen::QuaternionBase::slerp ( const Scalar t,
const QuaternionBase< OtherDerived > &  other 
) const
Returns
the spherical linear interpolation between the two quaternions *this and other at the parameter t in [0;1].

This represents an interpolation for a constant motion between *this and other, see also http://en.wikipedia.org/wiki/Slerp.

Definition at line 782 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ squaredNorm()

EIGEN_DEVICE_FUNC Scalar Eigen::QuaternionBase::squaredNorm ( ) const
inline
Returns
the squared norm of the quaternion's coefficients
See also
QuaternionBase::norm(), MatrixBase::squaredNorm()

Definition at line 120 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ toRotationMatrix()

EIGEN_DEVICE_FUNC QuaternionBase< Derived >::Matrix3 Eigen::QuaternionBase::toRotationMatrix ( ) const
inline
Returns
an equivalent 3x3 rotation matrix

Convert the quaternion to a 3x3 rotation matrix. The quaternion is required to be normalized, otherwise the result is undefined.

Definition at line 592 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ vec() [1/2]

EIGEN_DEVICE_FUNC VectorBlock<Coefficients,3> Eigen::QuaternionBase::vec ( )
inline
Returns
a vector expression of the imaginary part (x,y,z)

Definition at line 87 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ vec() [2/2]

const EIGEN_DEVICE_FUNC VectorBlock<const Coefficients,3> Eigen::QuaternionBase::vec ( ) const
inline
Returns
a read-only vector expression of the imaginary part (x,y,z)

Definition at line 84 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ w() [1/2]

EIGEN_DEVICE_FUNC NonConstCoeffReturnType Eigen::QuaternionBase::w ( )
inline
Returns
a reference to the w coefficient (if Derived is a non-const lvalue)

Definition at line 81 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ w() [2/2]

EIGEN_DEVICE_FUNC CoeffReturnType Eigen::QuaternionBase::w ( ) const
inline
Returns
the w coefficient

Definition at line 72 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ x() [1/2]

EIGEN_DEVICE_FUNC NonConstCoeffReturnType Eigen::QuaternionBase::x ( )
inline
Returns
a reference to the x coefficient (if Derived is a non-const lvalue)

Definition at line 75 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ x() [2/2]

EIGEN_DEVICE_FUNC CoeffReturnType Eigen::QuaternionBase::x ( ) const
inline
Returns
the x coefficient

Definition at line 66 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ y() [1/2]

EIGEN_DEVICE_FUNC NonConstCoeffReturnType Eigen::QuaternionBase::y ( )
inline
Returns
a reference to the y coefficient (if Derived is a non-const lvalue)

Definition at line 77 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ y() [2/2]

EIGEN_DEVICE_FUNC CoeffReturnType Eigen::QuaternionBase::y ( ) const
inline
Returns
the y coefficient

Definition at line 68 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ z() [1/2]

EIGEN_DEVICE_FUNC NonConstCoeffReturnType Eigen::QuaternionBase::z ( )
inline
Returns
a reference to the z coefficient (if Derived is a non-const lvalue)

Definition at line 79 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

◆ z() [2/2]

EIGEN_DEVICE_FUNC CoeffReturnType Eigen::QuaternionBase::z ( ) const
inline
Returns
the z coefficient

Definition at line 70 of file 3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h.

Friends And Related Function Documentation

◆ operator* [1/2]

EIGEN_DEVICE_FUNC friend Transform<Scalar,Dim,Affine> operator*
friend
Returns
the concatenation of a scaling l with the rotation r

Definition at line 80 of file RotationBase.h.

◆ operator* [2/2]

template<typename OtherDerived >
EIGEN_DEVICE_FUNC RotationMatrixType operator* ( typename OtherDerived  )
friend
Returns
the concatenation of a linear transformation l with the rotation r

Definition at line 76 of file RotationBase.h.

◆ operator<<

std::ostream& operator<< ( std::ostream &  s,
const QuaternionBase< Derived > &  q 
)
friend

The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Wed May 15 2024 15:29:06