Public Member Functions | Static Public Member Functions | List of all members
tf2::Quaternion Class Reference

The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform. More...

#include <Quaternion.h>

Inheritance diagram for tf2::Quaternion:
Inheritance graph
[legend]

Public Member Functions

tf2Scalar angle (const Quaternion &q) const
 Return the half angle between this quaternion and the other. More...
 
tf2Scalar angleShortestPath (const Quaternion &q) const
 Return the angle between this quaternion and the other along the shortest path. More...
 
tf2Scalar dot (const Quaternion &q) const
 Return the dot product between this quaternion and another. More...
 
TF2SIMD_FORCE_INLINE Quaternion farthest (const Quaternion &qd) const
 
tf2Scalar getAngle () const
 Return the angle [0, 2Pi] of rotation represented by this quaternion. More...
 
tf2Scalar getAngleShortestPath () const
 Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path. More...
 
Vector3 getAxis () const
 Return the axis of the rotation represented by this quaternion. More...
 
const TF2SIMD_FORCE_INLINE tf2ScalargetW () const
 
Quaternion inverse () const
 Return the inverse of this quaternion. More...
 
tf2Scalar length () const
 Return the length of the quaternion. More...
 
tf2Scalar length2 () const
 Return the length squared of the quaternion. More...
 
TF2SIMD_FORCE_INLINE Quaternion nearest (const Quaternion &qd) const
 
Quaternionnormalize ()
 Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1. More...
 
Quaternion normalized () const
 Return a normalized version of this quaternion. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const tf2Scalar &s) const
 Return a scaled version of this quaternion. More...
 
Quaternionoperator*= (const Quaternion &q)
 Multiply this quaternion by q on the right. More...
 
Quaternionoperator*= (const tf2Scalar &s)
 Scale this quaternion. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator+ (const Quaternion &q2) const
 Return the sum of this quaternion and the other. More...
 
TF2SIMD_FORCE_INLINE Quaternionoperator+= (const Quaternion &q)
 Add two quaternions. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator- () const
 Return the negative of this quaternion This simply negates each element. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q2) const
 Return the difference between this quaternion and the other. More...
 
Quaternionoperator-= (const Quaternion &q)
 Sutf2ract out a quaternion. More...
 
Quaternion operator/ (const tf2Scalar &s) const
 Return an inversely scaled versionof this quaternion. More...
 
Quaternionoperator/= (const tf2Scalar &s)
 Inversely scale this quaternion. More...
 
 Quaternion ()
 No initialization constructor. More...
 
 Quaternion (const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
 Constructor from scalars. More...
 
ROS_DEPRECATED Quaternion (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
 Constructor from Euler angles. More...
 
 Quaternion (const Vector3 &axis, const tf2Scalar &angle)
 Axis angle Constructor. More...
 
void setEuler (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
 Set the quaternion using Euler angles. More...
 
ROS_DEPRECATED void setEulerZYX (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
 Set the quaternion using euler angles. More...
 
void setRotation (const Vector3 &axis, const tf2Scalar &angle)
 Set the rotation using axis angle notation. More...
 
void setRPY (const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
 Set the quaternion using fixed axis RPY. More...
 
Quaternion slerp (const Quaternion &q, const tf2Scalar &t) const
 Return the quaternion which is the result of Spherical Linear Interpolation between this and the other quaternion. More...
 

Static Public Member Functions

static const QuaterniongetIdentity ()
 

Detailed Description

The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform.

Definition at line 30 of file Quaternion.h.

Constructor & Destructor Documentation

◆ Quaternion() [1/4]

tf2::Quaternion::Quaternion ( )
inline

No initialization constructor.

Definition at line 33 of file Quaternion.h.

◆ Quaternion() [2/4]

tf2::Quaternion::Quaternion ( const tf2Scalar x,
const tf2Scalar y,
const tf2Scalar z,
const tf2Scalar w 
)
inline

Constructor from scalars.

Definition at line 38 of file Quaternion.h.

◆ Quaternion() [3/4]

tf2::Quaternion::Quaternion ( const Vector3 &  axis,
const tf2Scalar angle 
)
inline

Axis angle Constructor.

Parameters
axisThe axis which the rotation is around
angleThe magnitude of the rotation around the angle (Radians)

Definition at line 44 of file Quaternion.h.

◆ Quaternion() [4/4]

ROS_DEPRECATED tf2::Quaternion::Quaternion ( const tf2Scalar yaw,
const tf2Scalar pitch,
const tf2Scalar roll 
)
inline

Constructor from Euler angles.

Parameters
yawAngle around Y unless TF2_EULER_DEFAULT_ZYX defined then Z
pitchAngle around X unless TF2_EULER_DEFAULT_ZYX defined then Y
rollAngle around Z unless TF2_EULER_DEFAULT_ZYX defined then X

Definition at line 52 of file Quaternion.h.

Member Function Documentation

◆ angle()

tf2Scalar tf2::Quaternion::angle ( const Quaternion q) const
inline

Return the half angle between this quaternion and the other.

Parameters
qThe other quaternion

Definition at line 212 of file Quaternion.h.

◆ angleShortestPath()

tf2Scalar tf2::Quaternion::angleShortestPath ( const Quaternion q) const
inline

Return the angle between this quaternion and the other along the shortest path.

Parameters
qThe other quaternion

Definition at line 220 of file Quaternion.h.

◆ dot()

tf2Scalar tf2::Quaternion::dot ( const Quaternion q) const
inline

Return the dot product between this quaternion and another.

Parameters
qThe other quaternion

Definition at line 156 of file Quaternion.h.

◆ farthest()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::farthest ( const Quaternion qd) const
inline
Todo:
document this and it's use

Definition at line 290 of file Quaternion.h.

◆ getAngle()

tf2Scalar tf2::Quaternion::getAngle ( ) const
inline

Return the angle [0, 2Pi] of rotation represented by this quaternion.

Definition at line 230 of file Quaternion.h.

◆ getAngleShortestPath()

tf2Scalar tf2::Quaternion::getAngleShortestPath ( ) const
inline

Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path.

Definition at line 237 of file Quaternion.h.

◆ getAxis()

Vector3 tf2::Quaternion::getAxis ( ) const
inline

Return the axis of the rotation represented by this quaternion.

Definition at line 249 of file Quaternion.h.

◆ getIdentity()

static const Quaternion& tf2::Quaternion::getIdentity ( )
inlinestatic

Definition at line 342 of file Quaternion.h.

◆ getW()

const TF2SIMD_FORCE_INLINE tf2Scalar& tf2::Quaternion::getW ( ) const
inline

Definition at line 348 of file Quaternion.h.

◆ inverse()

Quaternion tf2::Quaternion::inverse ( ) const
inline

Return the inverse of this quaternion.

Definition at line 259 of file Quaternion.h.

◆ length()

tf2Scalar tf2::Quaternion::length ( ) const
inline

Return the length of the quaternion.

Definition at line 168 of file Quaternion.h.

◆ length2()

tf2Scalar tf2::Quaternion::length2 ( ) const
inline

Return the length squared of the quaternion.

Definition at line 162 of file Quaternion.h.

◆ nearest()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::nearest ( const Quaternion qd) const
inline
Todo:
document this and it's use

Definition at line 301 of file Quaternion.h.

◆ normalize()

Quaternion& tf2::Quaternion::normalize ( )
inline

Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.

Definition at line 175 of file Quaternion.h.

◆ normalized()

Quaternion tf2::Quaternion::normalized ( ) const
inline

Return a normalized version of this quaternion.

Definition at line 206 of file Quaternion.h.

◆ operator*()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator* ( const tf2Scalar s) const
inline

Return a scaled version of this quaternion.

Parameters
sThe scale factor

Definition at line 183 of file Quaternion.h.

◆ operator*=() [1/2]

Quaternion& tf2::Quaternion::operator*= ( const Quaternion q)
inline

Multiply this quaternion by q on the right.

Parameters
qThe other quaternion Equivilant to this = this * q

Definition at line 146 of file Quaternion.h.

◆ operator*=() [2/2]

Quaternion& tf2::Quaternion::operator*= ( const tf2Scalar s)
inline

Scale this quaternion.

Parameters
sThe scalar to scale by

Definition at line 137 of file Quaternion.h.

◆ operator+()

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator+ ( const Quaternion q2) const
inline

Return the sum of this quaternion and the other.

Parameters
q2The other quaternion

Definition at line 267 of file Quaternion.h.

◆ operator+=()

TF2SIMD_FORCE_INLINE Quaternion& tf2::Quaternion::operator+= ( const Quaternion q)
inline

Add two quaternions.

Parameters
qThe quaternion to add to this one

Definition at line 121 of file Quaternion.h.

◆ operator-() [1/2]

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator- ( ) const
inline

Return the negative of this quaternion This simply negates each element.

Definition at line 284 of file Quaternion.h.

◆ operator-() [2/2]

TF2SIMD_FORCE_INLINE Quaternion tf2::Quaternion::operator- ( const Quaternion q2) const
inline

Return the difference between this quaternion and the other.

Parameters
q2The other quaternion

Definition at line 276 of file Quaternion.h.

◆ operator-=()

Quaternion& tf2::Quaternion::operator-= ( const Quaternion q)
inline

Sutf2ract out a quaternion.

Parameters
qThe quaternion to sutf2ract from this one

Definition at line 129 of file Quaternion.h.

◆ operator/()

Quaternion tf2::Quaternion::operator/ ( const tf2Scalar s) const
inline

Return an inversely scaled versionof this quaternion.

Parameters
sThe inverse scale factor

Definition at line 191 of file Quaternion.h.

◆ operator/=()

Quaternion& tf2::Quaternion::operator/= ( const tf2Scalar s)
inline

Inversely scale this quaternion.

Parameters
sThe scale factor

Definition at line 199 of file Quaternion.h.

◆ setEuler()

void tf2::Quaternion::setEuler ( const tf2Scalar yaw,
const tf2Scalar pitch,
const tf2Scalar roll 
)
inline

Set the quaternion using Euler angles.

Parameters
yawAngle around Y
pitchAngle around X
rollAngle around Z

Definition at line 75 of file Quaternion.h.

◆ setEulerZYX()

ROS_DEPRECATED void tf2::Quaternion::setEulerZYX ( const tf2Scalar yaw,
const tf2Scalar pitch,
const tf2Scalar roll 
)
inline

Set the quaternion using euler angles.

Parameters
yawAngle around Z
pitchAngle around Y
rollAngle around X

Definition at line 115 of file Quaternion.h.

◆ setRotation()

void tf2::Quaternion::setRotation ( const Vector3 &  axis,
const tf2Scalar angle 
)
inline

Set the rotation using axis angle notation.

Parameters
axisThe axis around which to rotate
angleThe magnitude of the rotation in Radians

Definition at line 63 of file Quaternion.h.

◆ setRPY()

void tf2::Quaternion::setRPY ( const tf2Scalar roll,
const tf2Scalar pitch,
const tf2Scalar yaw 
)
inline

Set the quaternion using fixed axis RPY.

Parameters
rollAngle around X
pitchAngle around Y
yawAngle around Z

Definition at line 95 of file Quaternion.h.

◆ slerp()

Quaternion tf2::Quaternion::slerp ( const Quaternion q,
const tf2Scalar t 
) const
inline

Return the quaternion which is the result of Spherical Linear Interpolation between this and the other quaternion.

Parameters
qThe other quaternion to interpolate with
tThe ratio between this and q to interpolate. If t = 0 the result is this, if t=1 the result is q. Slerp interpolates assuming constant velocity.

Definition at line 316 of file Quaternion.h.


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


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:11