Public Member Functions | Static Public Member Functions | List of all members
tf::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 tf::Quaternion:
Inheritance graph
[legend]

Public Member Functions

tfScalar angle (const Quaternion &q) const
 Return the half angle between this quaternion and the other. More...
 
tfScalar angleShortestPath (const Quaternion &q) const
 Return the angle between this quaternion and the other along the shortest path. More...
 
tfScalar dot (const Quaternion &q) const
 Return the dot product between this quaternion and another. More...
 
TFSIMD_FORCE_INLINE Quaternion farthest (const Quaternion &qd) const
 
tfScalar getAngle () const
 Return the angle [0, 2Pi] of rotation represented by this quaternion. More...
 
tfScalar 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 TFSIMD_FORCE_INLINE tfScalargetW () const
 
Quaternion inverse () const
 Return the inverse of this quaternion. More...
 
tfScalar length () const
 Return the length of the quaternion. More...
 
tfScalar length2 () const
 Return the length squared of the quaternion. More...
 
TFSIMD_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...
 
TFSIMD_FORCE_INLINE Quaternion operator* (const tfScalar &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 tfScalar &s)
 Scale this quaternion. More...
 
TFSIMD_FORCE_INLINE Quaternion operator+ (const Quaternion &q2) const
 Return the sum of this quaternion and the other. More...
 
TFSIMD_FORCE_INLINE Quaternionoperator+= (const Quaternion &q)
 Add two quaternions. More...
 
TFSIMD_FORCE_INLINE Quaternion operator- () const
 Return the negative of this quaternion This simply negates each element. More...
 
TFSIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q2) const
 Return the difference between this quaternion and the other. More...
 
Quaternionoperator-= (const Quaternion &q)
 Sutfract out a quaternion. More...
 
Quaternion operator/ (const tfScalar &s) const
 Return an inversely scaled versionof this quaternion. More...
 
Quaternionoperator/= (const tfScalar &s)
 Inversely scale this quaternion. More...
 
 Quaternion ()
 No initialization constructor. More...
 
 Quaternion (const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
 Constructor from scalars. More...
 
ROS_DEPRECATED Quaternion (const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
 Constructor from Euler angles. More...
 
 Quaternion (const Vector3 &axis, const tfScalar &angle)
 Axis angle Constructor. More...
 
void setEuler (const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
 Set the quaternion using Euler angles. More...
 
ROS_DEPRECATED void setEulerZYX (const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
 Set the quaternion using euler angles. More...
 
void setRotation (const Vector3 &axis, const tfScalar &angle)
 Set the rotation using axis angle notation. More...
 
void setRPY (const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
 Set the quaternion using fixed axis RPY. More...
 
Quaternion slerp (const Quaternion &q, const tfScalar &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]

tf::Quaternion::Quaternion ( )
inline

No initialization constructor.

Definition at line 33 of file Quaternion.h.

◆ Quaternion() [2/4]

tf::Quaternion::Quaternion ( const tfScalar x,
const tfScalar y,
const tfScalar z,
const tfScalar w 
)
inline

Constructor from scalars.

Definition at line 39 of file Quaternion.h.

◆ Quaternion() [3/4]

tf::Quaternion::Quaternion ( const Vector3 axis,
const tfScalar 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 45 of file Quaternion.h.

◆ Quaternion() [4/4]

ROS_DEPRECATED tf::Quaternion::Quaternion ( const tfScalar yaw,
const tfScalar pitch,
const tfScalar roll 
)
inline

Constructor from Euler angles.

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

Definition at line 53 of file Quaternion.h.

Member Function Documentation

◆ angle()

tfScalar tf::Quaternion::angle ( const Quaternion q) const
inline

Return the half angle between this quaternion and the other.

Parameters
qThe other quaternion

Definition at line 213 of file Quaternion.h.

◆ angleShortestPath()

tfScalar tf::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 221 of file Quaternion.h.

◆ dot()

tfScalar tf::Quaternion::dot ( const Quaternion q) const
inline

Return the dot product between this quaternion and another.

Parameters
qThe other quaternion

Definition at line 157 of file Quaternion.h.

◆ farthest()

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

Definition at line 290 of file Quaternion.h.

◆ getAngle()

tfScalar tf::Quaternion::getAngle ( ) const
inline

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

Definition at line 231 of file Quaternion.h.

◆ getAngleShortestPath()

tfScalar tf::Quaternion::getAngleShortestPath ( ) const
inline

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

Definition at line 238 of file Quaternion.h.

◆ getAxis()

Vector3 tf::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& tf::Quaternion::getIdentity ( )
inlinestatic

Definition at line 342 of file Quaternion.h.

◆ getW()

const TFSIMD_FORCE_INLINE tfScalar& tf::Quaternion::getW ( ) const
inline

Definition at line 348 of file Quaternion.h.

◆ inverse()

Quaternion tf::Quaternion::inverse ( ) const
inline

Return the inverse of this quaternion.

Definition at line 259 of file Quaternion.h.

◆ length()

tfScalar tf::Quaternion::length ( ) const
inline

Return the length of the quaternion.

Definition at line 169 of file Quaternion.h.

◆ length2()

tfScalar tf::Quaternion::length2 ( ) const
inline

Return the length squared of the quaternion.

Definition at line 163 of file Quaternion.h.

◆ nearest()

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

Definition at line 301 of file Quaternion.h.

◆ normalize()

Quaternion& tf::Quaternion::normalize ( )
inline

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

Definition at line 176 of file Quaternion.h.

◆ normalized()

Quaternion tf::Quaternion::normalized ( ) const
inline

Return a normalized version of this quaternion.

Definition at line 207 of file Quaternion.h.

◆ operator*()

TFSIMD_FORCE_INLINE Quaternion tf::Quaternion::operator* ( const tfScalar s) const
inline

Return a scaled version of this quaternion.

Parameters
sThe scale factor

Definition at line 184 of file Quaternion.h.

◆ operator*=() [1/2]

Quaternion& tf::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 147 of file Quaternion.h.

◆ operator*=() [2/2]

Quaternion& tf::Quaternion::operator*= ( const tfScalar s)
inline

Scale this quaternion.

Parameters
sThe scalar to scale by

Definition at line 138 of file Quaternion.h.

◆ operator+()

TFSIMD_FORCE_INLINE Quaternion tf::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+=()

TFSIMD_FORCE_INLINE Quaternion& tf::Quaternion::operator+= ( const Quaternion q)
inline

Add two quaternions.

Parameters
qThe quaternion to add to this one

Definition at line 122 of file Quaternion.h.

◆ operator-() [1/2]

TFSIMD_FORCE_INLINE Quaternion tf::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]

TFSIMD_FORCE_INLINE Quaternion tf::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& tf::Quaternion::operator-= ( const Quaternion q)
inline

Sutfract out a quaternion.

Parameters
qThe quaternion to sutfract from this one

Definition at line 130 of file Quaternion.h.

◆ operator/()

Quaternion tf::Quaternion::operator/ ( const tfScalar s) const
inline

Return an inversely scaled versionof this quaternion.

Parameters
sThe inverse scale factor

Definition at line 192 of file Quaternion.h.

◆ operator/=()

Quaternion& tf::Quaternion::operator/= ( const tfScalar s)
inline

Inversely scale this quaternion.

Parameters
sThe scale factor

Definition at line 200 of file Quaternion.h.

◆ setEuler()

void tf::Quaternion::setEuler ( const tfScalar yaw,
const tfScalar pitch,
const tfScalar roll 
)
inline

Set the quaternion using Euler angles.

Parameters
yawAngle around Y
pitchAngle around X
rollAngle around Z

Definition at line 76 of file Quaternion.h.

◆ setEulerZYX()

ROS_DEPRECATED void tf::Quaternion::setEulerZYX ( const tfScalar yaw,
const tfScalar pitch,
const tfScalar roll 
)
inline

Set the quaternion using euler angles.

Parameters
yawAngle around Z
pitchAngle around Y
rollAngle around X

Definition at line 116 of file Quaternion.h.

◆ setRotation()

void tf::Quaternion::setRotation ( const Vector3 axis,
const tfScalar 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 64 of file Quaternion.h.

◆ setRPY()

void tf::Quaternion::setRPY ( const tfScalar roll,
const tfScalar pitch,
const tfScalar yaw 
)
inline

Set the quaternion using fixed axis RPY.

Parameters
rollAngle around X
pitchAngle around Y
yawAngle around Z

Definition at line 96 of file Quaternion.h.

◆ slerp()

Quaternion tf::Quaternion::slerp ( const Quaternion q,
const tfScalar 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:


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:08