17 #ifndef TF2_QUATERNION_H_ 18 #define TF2_QUATERNION_H_ 37 : QuadWord(x, y, z, w)
52 #ifndef TF2_EULER_DEFAULT_ZYX 66 setValue(axis.x() * s, axis.y() * s, axis.z() * s,
84 setValue(cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
85 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
86 sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
87 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
104 setValue(sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
105 cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
106 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
107 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
121 m_floats[0] += q.x(); m_floats[1] += q.y(); m_floats[2] += q.z(); m_floats[3] += q.m_floats[3];
129 m_floats[0] -= q.x(); m_floats[1] -= q.y(); m_floats[2] -= q.z(); m_floats[3] -= q.m_floats[3];
137 m_floats[0] *= s; m_floats[1] *= s; m_floats[2] *= s; m_floats[3] *= s;
146 setValue(m_floats[3] * q.x() + m_floats[0] * q.m_floats[3] + m_floats[1] * q.z() - m_floats[2] * q.y(),
147 m_floats[3] * q.y() + m_floats[1] * q.m_floats[3] + m_floats[2] * q.x() - m_floats[0] * q.z(),
148 m_floats[3] * q.z() + m_floats[2] * q.m_floats[3] + m_floats[0] * q.y() - m_floats[1] * q.x(),
149 m_floats[3] * q.m_floats[3] - m_floats[0] * q.x() - m_floats[1] * q.y() - m_floats[2] * q.z());
156 return m_floats[0] * q.x() + m_floats[1] * q.y() + m_floats[2] * q.z() + m_floats[3] * q.m_floats[3];
183 return Quaternion(x() * s, y() * s, z() * s, m_floats[3] * s);
238 if (m_floats[3] >= 0)
251 return Vector3(1.0, 0.0, 0.0);
253 return Vector3(m_floats[0] / s, m_floats[1] / s, m_floats[2] / s);
259 return Quaternion(-m_floats[0], -m_floats[1], -m_floats[2], m_floats[3]);
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) )
323 return Quaternion((m_floats[0] * s0 + -q.x() * s1) * d,
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);
328 return Quaternion((m_floats[0] * s0 + q.x() * 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());
446 Vector3 c = v0.cross(v1);
459 return Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,s * 0.5f);
Quaternion & operator/=(const tf2Scalar &s)
Inversely scale this quaternion.
#define TF2SIMD_FORCE_INLINE
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuat(const Vector3 &v0, const Vector3 &v1)
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
Set the quaternion using fixed axis RPY.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x)
Quaternion normalized() const
Return a normalized version of this quaternion.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Acos(tf2Scalar x)
static const Quaternion & getIdentity()
TF2SIMD_FORCE_INLINE Quaternion farthest(const Quaternion &qd) const
TF2SIMD_FORCE_INLINE const tf2Scalar & getW() const
Quaternion operator/(const tf2Scalar &s) const
Return an inversely scaled versionof this quaternion.
tf2Scalar length() const
Return the length of the quaternion.
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
Quaternion inverse() const
Return the inverse of this quaternion.
tf2Scalar getAngleShortestPath() const
Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path...
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
Quaternion()
No initialization constructor.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Pow(tf2Scalar x, tf2Scalar y)
Quaternion & normalize()
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
tf2Scalar length2() const
Return the length squared of the quaternion.
tf2Scalar getAngle() const
Return the angle [0, 2Pi] of rotation represented by this quaternion.
Quaternion slerp(const Quaternion &q, const tf2Scalar &t) const
Return the quaternion which is the result of Spherical Linear Interpolation between this and the othe...
void setEulerZYX(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll) __attribute__((deprecated))
Set the quaternion using euler angles.
TF2SIMD_FORCE_INLINE Quaternion nearest(const Quaternion &qd) const
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2(Vector3 &v0, Vector3 &v1)
Quaternion(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Constructor from scalars.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sin(tf2Scalar x)
tf2Scalar dot(const Quaternion &q) const
Return the dot product between this quaternion and another.
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
Set the quaternion using Euler angles.
TF2SIMD_FORCE_INLINE Quaternion & operator+=(const Quaternion &q)
Add two quaternions.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x)
void setRotation(const Vector3 &axis, const tf2Scalar &angle)
Set the rotation using axis angle notation.
TF2SIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
TF2SIMD_FORCE_INLINE Quaternion operator-() const
Return the negative of this quaternion This simply negates each element.
Quaternion & operator-=(const Quaternion &q)
Sutf2ract out a quaternion.
Quaternion & operator*=(const Quaternion &q)
Multiply this quaternion by q on the right.
Vector3 getAxis() const
Return the axis of the rotation represented by this quaternion.
tf2Scalar angle(const Quaternion &q) const
Return the ***half*** angle between this quaternion and the other.
tf2Scalar angleShortestPath(const Quaternion &q) const
Return the angle between this quaternion and the other along the shortest path.
TF2SIMD_FORCE_INLINE Quaternion operator+(const Quaternion &q2) const
Return the sum of this quaternion and the other.
TF2SIMD_FORCE_INLINE Quaternion operator*(const tf2Scalar &s) const
Return a scaled version of this quaternion.
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Quaternion(const Vector3 &axis, const tf2Scalar &angle)
Axis angle Constructor.
Quaternion & operator*=(const tf2Scalar &s)
Scale this quaternion.
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q2) const
Return the difference between this quaternion and the other.
Quaternion(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll) __attribute__((deprecated))
Constructor from Euler angles.