The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform. More...
#include <Quaternion.h>

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... | |
| TF2SIMD_FORCE_INLINE const tf2Scalar & | getW () 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 |
| Quaternion & | normalize () |
| 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... | |
| Quaternion & | operator*= (const tf2Scalar &s) |
| Scale this quaternion. More... | |
| Quaternion & | operator*= (const Quaternion &q) |
| Multiply this quaternion by q on the right. More... | |
| TF2SIMD_FORCE_INLINE Quaternion | operator+ (const Quaternion &q2) const |
| Return the sum of this quaternion and the other. More... | |
| TF2SIMD_FORCE_INLINE Quaternion & | operator+= (const Quaternion &q) |
| Add two quaternions. More... | |
| TF2SIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q2) const |
| Return the difference between this quaternion and the other. More... | |
| TF2SIMD_FORCE_INLINE Quaternion | operator- () const |
| Return the negative of this quaternion This simply negates each element. More... | |
| Quaternion & | operator-= (const Quaternion &q) |
| Sutf2ract out a quaternion. More... | |
| Quaternion | operator/ (const tf2Scalar &s) const |
| Return an inversely scaled versionof this quaternion. More... | |
| Quaternion & | operator/= (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... | |
| Quaternion (const Vector3 &axis, const tf2Scalar &angle) | |
| Axis angle Constructor. More... | |
| Quaternion (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll) __attribute__((deprecated)) | |
| Constructor from Euler angles. More... | |
| void | setEuler (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll) |
| Set the quaternion using Euler angles. More... | |
| void | setEulerZYX (const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll) __attribute__((deprecated)) |
| 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 Quaternion & | getIdentity () |
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform.
Definition at line 28 of file Quaternion.h.
|
inline |
No initialization constructor.
Definition at line 31 of file Quaternion.h.
|
inline |
Constructor from scalars.
Definition at line 36 of file Quaternion.h.
|
inline |
Axis angle Constructor.
| axis | The axis which the rotation is around |
| angle | The magnitude of the rotation around the angle (Radians) |
Definition at line 42 of file Quaternion.h.
|
inline |
Constructor from Euler angles.
| yaw | Angle around Y unless TF2_EULER_DEFAULT_ZYX defined then Z |
| pitch | Angle around X unless TF2_EULER_DEFAULT_ZYX defined then Y |
| roll | Angle around Z unless TF2_EULER_DEFAULT_ZYX defined then X |
Definition at line 50 of file Quaternion.h.
|
inline |
Return the ***half*** angle between this quaternion and the other.
| q | The other quaternion |
Definition at line 210 of file Quaternion.h.
|
inline |
Return the angle between this quaternion and the other along the shortest path.
| q | The other quaternion |
Definition at line 218 of file Quaternion.h.
|
inline |
Return the dot product between this quaternion and another.
| q | The other quaternion |
Definition at line 154 of file Quaternion.h.
|
inline |
Definition at line 288 of file Quaternion.h.
|
inline |
Return the angle [0, 2Pi] of rotation represented by this quaternion.
Definition at line 228 of file Quaternion.h.
|
inline |
Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path.
Definition at line 235 of file Quaternion.h.
|
inline |
Return the axis of the rotation represented by this quaternion.
Definition at line 247 of file Quaternion.h.
|
inlinestatic |
Definition at line 340 of file Quaternion.h.
|
inline |
Definition at line 346 of file Quaternion.h.
|
inline |
Return the inverse of this quaternion.
Definition at line 257 of file Quaternion.h.
|
inline |
Return the length of the quaternion.
Definition at line 166 of file Quaternion.h.
|
inline |
Return the length squared of the quaternion.
Definition at line 160 of file Quaternion.h.
|
inline |
Definition at line 299 of file Quaternion.h.
|
inline |
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
Definition at line 173 of file Quaternion.h.
|
inline |
Return a normalized version of this quaternion.
Definition at line 204 of file Quaternion.h.
|
inline |
Return a scaled version of this quaternion.
| s | The scale factor |
Definition at line 181 of file Quaternion.h.
|
inline |
Scale this quaternion.
| s | The scalar to scale by |
Definition at line 135 of file Quaternion.h.
|
inline |
Multiply this quaternion by q on the right.
| q | The other quaternion Equivilant to this = this * q |
Definition at line 144 of file Quaternion.h.
|
inline |
Return the sum of this quaternion and the other.
| q2 | The other quaternion |
Definition at line 265 of file Quaternion.h.
|
inline |
Add two quaternions.
| q | The quaternion to add to this one |
Definition at line 119 of file Quaternion.h.
|
inline |
Return the difference between this quaternion and the other.
| q2 | The other quaternion |
Definition at line 274 of file Quaternion.h.
|
inline |
Return the negative of this quaternion This simply negates each element.
Definition at line 282 of file Quaternion.h.
|
inline |
Sutf2ract out a quaternion.
| q | The quaternion to sutf2ract from this one |
Definition at line 127 of file Quaternion.h.
|
inline |
Return an inversely scaled versionof this quaternion.
| s | The inverse scale factor |
Definition at line 189 of file Quaternion.h.
|
inline |
Inversely scale this quaternion.
| s | The scale factor |
Definition at line 197 of file Quaternion.h.
|
inline |
Set the quaternion using Euler angles.
| yaw | Angle around Y |
| pitch | Angle around X |
| roll | Angle around Z |
Definition at line 73 of file Quaternion.h.
|
inline |
Set the quaternion using euler angles.
| yaw | Angle around Z |
| pitch | Angle around Y |
| roll | Angle around X |
Definition at line 113 of file Quaternion.h.
|
inline |
Set the rotation using axis angle notation.
| axis | The axis around which to rotate |
| angle | The magnitude of the rotation in Radians |
Definition at line 61 of file Quaternion.h.
|
inline |
Set the quaternion using fixed axis RPY.
| roll | Angle around X |
| pitch | Angle around Y |
| yaw | Angle around Z |
Definition at line 93 of file Quaternion.h.
|
inline |
Return the quaternion which is the result of Spherical Linear Interpolation between this and the other quaternion.
| q | The other quaternion to interpolate with |
| t | The 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 314 of file Quaternion.h.