maliput
Quaternion Class Reference

Detailed Description

A Quaternion representation.

#include <include/maliput/math/quaternion.h>

Public Member Functions

 MALIPUT_DEFAULT_COPY_AND_MOVE_AND_ASSIGN (Quaternion)
 
 Quaternion ()
 Constructs a Quaternion initialized to \( 1+0i+0j+0k \). More...
 
 Quaternion (double w, double x, double y, double z)
 Constructs a Quaternion and initializes it to \( w+xi+yj+zk \). More...
 
 Quaternion (double angle, const Vector3 &axis)
 Constructs a Quaternion expressed by angle rotation around axis vector. More...
 
 Quaternion (const Vector4 &coeffs)
 Constructs a Quaternion from a 4D vector matching all its components. More...
 
 Quaternion (const Matrix3 &rotation_matrix)
 Constructs a Quaternion from a 3D rotation matrix. More...
 
double w () const
 
double x () const
 
double y () const
 
double z () const
 
doublew ()
 
doublex ()
 
doubley ()
 
doublez ()
 
Vector3 vec () const
 }@ More...
 
Vector4 coeffs () const
 
Quaternionset_identity ()
 Sets the identity quaternion values as if it was initialized with \( [1, 0, 0, 0] \). More...
 
double squared_norm () const
 
double norm () const
 
void normalize ()
 Normalizes (norm() == 1) this quaternion coefficients. More...
 
Quaternion normalized () const
 
double dot (const Quaternion &other) const
 Executes the dot product between this quaternion coefficients and other. More...
 
double AngularDistance (const Quaternion &other) const
 Computes the angular distance between the rotation of this quaternion and other. More...
 
Matrix3 ToRotationMatrix () const
 
void SetFromTwoVectors (const Vector3 &a, const Vector3 &b)
 Sets this quaternion with the coefficients that makes a transform into b. More...
 
Quaternion operator* (const Quaternion &q) const
 Product operator overload. More...
 
Quaternionoperator*= (const Quaternion &q)
 Product and assignment operator overload. More...
 
Vector3 operator* (const Vector3 &v) const
 Forwards the call to TransformVector(v). More...
 
bool operator== (const Quaternion &other) const
 Operator equal to overload. More...
 
bool operator!= (const Quaternion &other) const
 Operator not equal to overload. More...
 
Quaternion Inverse () const
 
Quaternion conjugate () const
 
Quaternion Slerp (double t, const Quaternion &other) const
 
bool IsApprox (const Quaternion &other, double precision) const
 Evaluates if this quaternion is almost equal to other up to precision tolerance. More...
 
Vector3 TransformVector (const Vector3 &v) const
 Applies this quaternion transformation to v 3D vector. More...
 

Static Public Member Functions

static Quaternion Identity ()
 
static Quaternion FromTwoVectors (const Vector3 &a, const Vector3 &b)
 

Static Public Attributes

static constexpr double kTolerance {1e-15}
 

Constructor & Destructor Documentation

◆ Quaternion() [1/5]

Constructs a Quaternion initialized to \( 1+0i+0j+0k \).

◆ Quaternion() [2/5]

Quaternion ( double  w,
double  x,
double  y,
double  z 
)

Constructs a Quaternion and initializes it to \( w+xi+yj+zk \).

Parameters
wThe real \( w \) coefficient.
xThe internal \( x \) coefficient.
yThe internal \( y \) coefficient.
zThe internal \( z \)s coefficient.

◆ Quaternion() [3/5]

Quaternion ( double  angle,
const Vector3 axis 
)

Constructs a Quaternion expressed by angle rotation around axis vector.

Parameters
angleA scalar representing an angle in radians.
axisA 3D vector representing the rotation angle.

◆ Quaternion() [4/5]

Quaternion ( const Vector4 coeffs)
explicit

Constructs a Quaternion from a 4D vector matching all its components.

Parameters
coeffsA 4D vector whose first element is \( w \), second element is \( x \), third element is \( y \) and fourth element is \( z \).

◆ Quaternion() [5/5]

Quaternion ( const Matrix3 rotation_matrix)
explicit

Constructs a Quaternion from a 3D rotation matrix.

Parameters
rotation_matrixA 3x3 matrix whose elements represent a rotation matrix.
See also
https://bitbucket.org/ignitionrobotics/ign-math/src/ac54456ab8c431a59fbecfa1cf4b7c2b6f96cb33/include/ignition/math/Quaternion.hh#lines-461:503

Member Function Documentation

◆ AngularDistance()

double AngularDistance ( const Quaternion other) const

Computes the angular distance between the rotation of this quaternion and other.

Parameters
otherA Quaternion.
Returns
The angle in radians between this rotation and other's rotation.

◆ coeffs()

Vector4 coeffs ( ) const
Returns
This quaternion coefficients: \( [w, x, y, z] \).

◆ conjugate()

Quaternion conjugate ( ) const
Returns
A Quaternion that results from conjugating this.

◆ dot()

double dot ( const Quaternion other) const

Executes the dot product between this quaternion coefficients and other.

Parameters
otherA Quaternion.
Returns
The dot product between this quaternion and other.

◆ FromTwoVectors()

Quaternion FromTwoVectors ( const Vector3 a,
const Vector3 b 
)
static

◆ Identity()

Quaternion Identity ( )
static
Returns
A quaternion initialized with \( [1, 0, 0, 0] \).

◆ Inverse()

Quaternion Inverse ( ) const
Returns
A Quaternion that results from computing the inverse rotation.

◆ IsApprox()

bool IsApprox ( const Quaternion other,
double  precision 
) const

Evaluates if this quaternion is almost equal to other up to precision tolerance.

this quaternion is approximately equal to other when the squared norm of the vector difference from both quaternion's coefficients is smaller than the minimum squared norm between this and other scaled with the squared precision.

Parameters
otherA Quaternion to compare with.
precisionThe tolerance.
Returns
true When this quaternion is almost equal to other up to precision tolerance.

◆ MALIPUT_DEFAULT_COPY_AND_MOVE_AND_ASSIGN()

MALIPUT_DEFAULT_COPY_AND_MOVE_AND_ASSIGN ( Quaternion  )

◆ norm()

double norm ( ) const
Returns
The norm of this quaternion.

◆ normalize()

void normalize ( )

Normalizes (norm() == 1) this quaternion coefficients.

When the norm() < kTolerance, the result is equivalent to call set_identity().

◆ normalized()

Quaternion normalized ( ) const
Returns
*this quaternion with normalized coefficients.

◆ operator!=()

bool operator!= ( const Quaternion other) const

Operator not equal to overload.

Performs a coefficient wise comparison.

Parameters
otherA quaternion to compare to this quaternion.
Returns
true When this' and other's coefficients are not equal.

◆ operator*() [1/2]

Quaternion operator* ( const Quaternion q) const

Product operator overload.

Parameters
qA Quaternion.
Returns
A quaternion that results from \( `this` * `q` \).
See also
https://bitbucket.org/ignitionrobotics/ign-math/src/ac54456ab8c431a59fbecfa1cf4b7c2b6f96cb33/include/ignition/math/Quaternion.hh#lines-638:648

◆ operator*() [2/2]

Vector3 operator* ( const Vector3 v) const

Forwards the call to TransformVector(v).

◆ operator*=()

Quaternion & operator*= ( const Quaternion q)

Product and assignment operator overload.

Parameters
qA Quaternion.
Returns
A mutable reference to *this initialized with \( `this` * `q` \).
See also
https://bitbucket.org/ignitionrobotics/ign-math/src/ac54456ab8c431a59fbecfa1cf4b7c2b6f96cb33/include/ignition/math/Quaternion.hh#lines-638:648

◆ operator==()

bool operator== ( const Quaternion other) const

Operator equal to overload.

Performs a coefficient wise comparison.

Parameters
otherA quaternion to compare to this quaternion.
Returns
true When this' and other's coefficients are equal.

◆ set_identity()

Quaternion& set_identity ( )

Sets the identity quaternion values as if it was initialized with \( [1, 0, 0, 0] \).

Returns
*this.

◆ SetFromTwoVectors()

void SetFromTwoVectors ( const Vector3 a,
const Vector3 b 
)

Sets this quaternion with the coefficients that makes a transform into b.

Parameters
aA 3D vector.
bA 3D vector.
See also
https://bitbucket.org/ignitionrobotics/ign-math/src/ac54456ab8c431a59fbecfa1cf4b7c2b6f96cb33/include/ignition/math/Quaternion.hh#lines-505:582

◆ Slerp()

Quaternion Slerp ( double  t,
const Quaternion other 
) const
Returns
The spherical linear interpolation between the two quaternions *this and other at the parameter t.
Parameters
tThe interpolation parameter. It must be in [0; 1].
otherA quaternion.

◆ squared_norm()

double squared_norm ( ) const
Returns
The squared norm of this quaternion.

◆ ToRotationMatrix()

Matrix3 ToRotationMatrix ( ) const
Returns
A rotation Matrix3 equivalent to this normalized quaternion rotation.

◆ TransformVector()

Vector3 TransformVector ( const Vector3 v) const

Applies this quaternion transformation to v 3D vector.

Parameters
vA 3D vector.
Returns
A transformed 3D vector.

◆ vec()

Vector3 vec ( ) const

}@

Returns
This quaternion vector: \( [x, y, z] \).

◆ w() [1/2]

double& w ( )

◆ w() [2/2]

double w ( ) const

◆ x() [1/2]

double& x ( )

◆ x() [2/2]

double x ( ) const

◆ y() [1/2]

double& y ( )

◆ y() [2/2]

double y ( ) const

◆ z() [1/2]

double& z ( )

◆ z() [2/2]

double z ( ) const

Member Data Documentation

◆ kTolerance

constexpr double kTolerance {1e-15}
staticconstexpr

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