17 #ifndef TF_QUATERNION_H_ 18 #define TF_QUATERNION_H_ 38 : QuadWord(x, y, z, w)
53 #ifndef TF_EULER_DEFAULT_ZYX 85 setValue(cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
86 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
87 sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
88 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
105 setValue(sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
106 cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
107 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
108 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
268 return Quaternion(q1.x() + q2.x(), q1.y() + q2.y(), q1.z() + q2.z(), q1.m_floats[3] + q2.m_floats[3]);
277 return Quaternion(q1.x() - q2.x(), q1.y() - q2.y(), q1.z() - q2.z(), q1.m_floats[3] - q2.m_floats[3]);
285 return Quaternion( - q2.x(), - q2.y(), - q2.z(), - q2.m_floats[3]);
293 if( diff.
dot(diff) > sum.
dot(sum) )
304 if( diff.
dot(diff) < sum.
dot(sum) )
324 (
m_floats[1] * s0 + -q.y() * s1) * d,
325 (
m_floats[2] * s0 + -q.z() * s1) * d,
326 (
m_floats[3] * s0 + -q.m_floats[3] * s1) * d);
329 (
m_floats[1] * s0 + q.y() * s1) * d,
330 (
m_floats[2] * s0 + q.z() * s1) * d,
331 (
m_floats[3] * s0 + q.m_floats[3] * s1) * d);
356 return Quaternion(-q.x(), -q.y(), -q.z(), -q.w());
364 return Quaternion(q1.w() * q2.x() + q1.x() * q2.w() + q1.y() * q2.z() - q1.z() * q2.y(),
365 q1.w() * q2.y() + q1.y() * q2.w() + q1.z() * q2.x() - q1.x() * q2.z(),
366 q1.w() * q2.z() + q1.z() * q2.w() + q1.x() * q2.y() - q1.y() * q2.x(),
367 q1.w() * q2.w() - q1.x() * q2.x() - q1.y() * q2.y() - q1.z() * q2.z());
373 return Quaternion( q.w() * w.
x() + q.y() * w.
z() - q.z() * w.
y(),
374 q.w() * w.
y() + q.z() * w.
x() - q.x() * w.
z(),
375 q.w() * w.
z() + q.x() * w.
y() - q.y() * w.
x(),
376 -q.x() * w.
x() - q.y() * w.
y() - q.z() * w.
z());
382 return Quaternion( w.
x() * q.w() + w.
y() * q.z() - w.
z() * q.y(),
383 w.
y() * q.w() + w.
z() * q.x() - w.
x() * q.z(),
384 w.
z() * q.w() + w.
x() * q.y() - w.
y() * q.x(),
385 -w.
x() * q.x() - w.
y() * q.y() - w.
z() * q.z());
432 return q1.
slerp(q2, t);
440 return Vector3(q.getX(),q.getY(),q.getZ());
tfScalar length() const
Return the length of the quaternion.
TFSIMD_FORCE_INLINE Quaternion operator+(const Quaternion &q2) const
Return the sum of this quaternion and the other.
tfScalar getAngle() const
Return the angle [0, 2Pi] of rotation represented by this quaternion.
TFSIMD_FORCE_INLINE Quaternion operator-() const
Return the negative of this quaternion This simply negates each element.
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
double tfScalar
The tfScalar type abstracts floating point numbers, to easily switch between double and single floati...
tfScalar length2() const
Return the length squared of the quaternion.
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z)
TFSIMD_FORCE_INLINE Quaternion operator*(const tfScalar &s) const
Return a scaled version of this quaternion.
Quaternion & operator/=(const tfScalar &s)
Inversely scale this quaternion.
tfScalar getAngleShortestPath() const
Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path...
Quaternion(const Vector3 &axis, const tfScalar &angle)
Axis angle Constructor.
TFSIMD_FORCE_INLINE const tfScalar & getY() const
Return the y value.
Quaternion & normalize()
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
TFSIMD_FORCE_INLINE const tfScalar & getW() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
Return the y value.
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
Return the z value.
Quaternion slerp(const Quaternion &q, const tfScalar &t) const
Return the quaternion which is the result of Spherical Linear Interpolation between this and the othe...
Quaternion & operator*=(const tfScalar &s)
Scale this quaternion.
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
Return the cross product between this and another vector.
Quaternion & operator*=(const Quaternion &q)
Multiply this quaternion by q on the right.
TFSIMD_FORCE_INLINE const tfScalar & x() const
Return the x value.
TFSIMD_FORCE_INLINE void tfPlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x)
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const
Return the dot product.
tfScalar angle(const Quaternion &q) const
Return the ***half*** angle between this quaternion and the other.
TFSIMD_FORCE_INLINE tfScalar tfAcos(tfScalar x)
TFSIMD_FORCE_INLINE const tfScalar & z() const
Return the z value.
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
Set the quaternion using fixed axis RPY.
static const Quaternion & getIdentity()
TFSIMD_FORCE_INLINE Vector3()
No initialization constructor.
Vector3 getAxis() const
Return the axis of the rotation represented by this quaternion.
TFSIMD_FORCE_INLINE const tfScalar & y() const
Return the y value.
tfScalar dot(const Quaternion &q) const
Return the dot product between this quaternion and another.
TFSIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
void setEulerZYX(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll) __attribute__((deprecated))
Set the quaternion using euler angles.
#define TFSIMD_FORCE_INLINE
TFSIMD_FORCE_INLINE const tfScalar & x() const
Return the x value.
Quaternion operator/(const tfScalar &s) const
Return an inversely scaled versionof this quaternion.
void setEuler(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
Set the quaternion using Euler angles.
TFSIMD_FORCE_INLINE const tfScalar & z() const
Return the z value.
TFSIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q2) const
Return the difference between this quaternion and the other.
Quaternion inverse() const
Return the inverse of this quaternion.
TFSIMD_FORCE_INLINE Vector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
TFSIMD_FORCE_INLINE Quaternion nearest(const Quaternion &qd) const
Quaternion()
No initialization constructor.
TFSIMD_FORCE_INLINE tfScalar tfSqrt(tfScalar x)
TFSIMD_FORCE_INLINE const tfScalar & w() const
Return the w value.
Quaternion(const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
Constructor from scalars.
TFSIMD_FORCE_INLINE Quaternion farthest(const Quaternion &qd) const
TFSIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2(Vector3 &v0, Vector3 &v1)
Quaternion & operator-=(const Quaternion &q)
Sutfract out a quaternion.
TFSIMD_FORCE_INLINE Quaternion & operator+=(const Quaternion &q)
Add two quaternions.
Quaternion(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll) __attribute__((deprecated))
Constructor from Euler angles.
TFSIMD_FORCE_INLINE const tfScalar & getX() const
Return the x value.
TFSIMD_FORCE_INLINE tfScalar tfSin(tfScalar x)
TFSIMD_FORCE_INLINE Quaternion shortestArcQuat(const Vector3 &v0, const Vector3 &v1)
tfScalar angleShortestPath(const Quaternion &q) const
Return the angle between this quaternion and the other along the shortest path.
void setRotation(const Vector3 &axis, const tfScalar &angle)
Set the rotation using axis angle notation.
TFSIMD_FORCE_INLINE tfScalar tfPow(tfScalar x, tfScalar y)
Quaternion normalized() const
Return a normalized version of this quaternion.
TFSIMD_FORCE_INLINE tfScalar length() const
Return the length of the vector.
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...
tf::tfVector4 __attribute__