Go to the documentation of this file.
17 #ifndef TF_QUATERNION_H_
18 #define TF_QUATERNION_H_
40 : QuadWord(x, y, z, w)
55 #ifndef TF_EULER_DEFAULT_ZYX
69 setValue(axis.x() *
s, axis.y() *
s, axis.z() *
s,
87 setValue(cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
88 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
89 sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
90 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
107 setValue(sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
108 cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
109 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
110 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
124 m_floats[0] += q.x(); m_floats[1] += q.y(); m_floats[2] += q.z(); m_floats[3] += q.m_floats[3];
132 m_floats[0] -= q.x(); m_floats[1] -= q.y(); m_floats[2] -= q.z(); m_floats[3] -= q.m_floats[3];
140 m_floats[0] *=
s; m_floats[1] *=
s; m_floats[2] *=
s; m_floats[3] *=
s;
149 setValue(m_floats[3] * q.x() + m_floats[0] * q.m_floats[3] + m_floats[1] * q.z() - m_floats[2] * q.y(),
150 m_floats[3] * q.y() + m_floats[1] * q.m_floats[3] + m_floats[2] * q.x() - m_floats[0] * q.z(),
151 m_floats[3] * q.z() + m_floats[2] * q.m_floats[3] + m_floats[0] * q.y() - m_floats[1] * q.x(),
152 m_floats[3] * q.m_floats[3] - m_floats[0] * q.x() - m_floats[1] * q.y() - m_floats[2] * q.z());
159 return m_floats[0] * q.x() + m_floats[1] * q.y() + m_floats[2] * q.z() + m_floats[3] * q.m_floats[3];
255 return Vector3(m_floats[0] /
s, m_floats[1] /
s, m_floats[2] /
s);
261 return Quaternion(-m_floats[0], -m_floats[1], -m_floats[2], m_floats[3]);
270 return Quaternion(q1.x() + q2.x(), q1.y() + q2.y(), q1.z() + q2.z(), q1.m_floats[3] + q2.m_floats[3]);
279 return Quaternion(q1.x() - q2.x(), q1.y() - q2.y(), q1.z() - q2.z(), q1.m_floats[3] - q2.m_floats[3]);
287 return Quaternion( - q2.x(), - q2.y(), - q2.z(), - q2.m_floats[3]);
295 if( diff.
dot(diff) > sum.
dot(sum) )
306 if( diff.
dot(diff) < sum.
dot(sum) )
325 return Quaternion((m_floats[0] * s0 + -q.x() * s1) *
d,
326 (m_floats[1] * s0 + -q.y() * s1) *
d,
327 (m_floats[2] * s0 + -q.z() * s1) *
d,
328 (m_floats[3] * s0 + -q.m_floats[3] * s1) *
d);
330 return Quaternion((m_floats[0] * s0 + q.x() * s1) *
d,
331 (m_floats[1] * s0 + q.y() * s1) *
d,
332 (m_floats[2] * s0 + q.z() * s1) *
d,
333 (m_floats[3] * s0 + q.m_floats[3] * s1) *
d);
358 return Quaternion(-q.x(), -q.y(), -q.z(), -q.w());
366 return Quaternion(q1.w() * q2.x() + q1.x() * q2.w() + q1.y() * q2.z() - q1.z() * q2.y(),
367 q1.w() * q2.y() + q1.y() * q2.w() + q1.z() * q2.x() - q1.x() * q2.z(),
368 q1.w() * q2.z() + q1.z() * q2.w() + q1.x() * q2.y() - q1.y() * q2.x(),
369 q1.w() * q2.w() - q1.x() * q2.x() - q1.y() * q2.y() - q1.z() * q2.z());
375 return Quaternion( q.w() * w.x() + q.y() * w.z() - q.z() * w.y(),
376 q.w() * w.y() + q.z() * w.x() - q.x() * w.z(),
377 q.w() * w.z() + q.x() * w.y() - q.y() * w.x(),
378 -q.x() * w.x() - q.y() * w.y() - q.z() * w.z());
384 return Quaternion( w.x() * q.w() + w.y() * q.z() - w.z() * q.y(),
385 w.y() * q.w() + w.z() * q.x() - w.x() * q.z(),
386 w.z() * q.w() + w.x() * q.y() - w.y() * q.x(),
387 -w.x() * q.x() - w.y() * q.y() - w.z() * q.z());
434 return q1.
slerp(q2, t);
442 return Vector3(q.getX(),q.getY(),q.getZ());
461 return Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,
s * 0.5f);
Quaternion & normalize()
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
TFSIMD_FORCE_INLINE tfScalar tfAcos(tfScalar x)
Quaternion normalized() const
Return a normalized version of this quaternion.
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 Quaternion operator+(const Quaternion &q2) const
Return the sum of this quaternion and the other.
TFSIMD_FORCE_INLINE tfScalar angleShortestPath(const Quaternion &q1, const Quaternion &q2)
Return the shortest angle between two quaternions.
TFSIMD_FORCE_INLINE Quaternion nearest(const Quaternion &qd) const
TFSIMD_FORCE_INLINE Quaternion shortestArcQuat(const Vector3 &v0, const Vector3 &v1)
#define TFSIMD_FORCE_INLINE
tfScalar length() const
Return the length of the quaternion.
Quaternion()
No initialization constructor.
Quaternion inverse() const
Return the inverse of this quaternion.
TFSIMD_FORCE_INLINE tfScalar tfSqrt(tfScalar x)
tfScalar angleShortestPath(const Quaternion &q) const
Return the angle between this quaternion and the other along the shortest path.
TFSIMD_FORCE_INLINE void tfPlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
TFSIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
Return the result of spherical linear interpolation betwen two quaternions.
TFSIMD_FORCE_INLINE tfScalar tfSin(tfScalar x)
TFSIMD_FORCE_INLINE Quaternion & operator+=(const Quaternion &q)
Add two quaternions.
TFSIMD_FORCE_INLINE Quaternion operator*(const tfScalar &s) const
Return a scaled version of this quaternion.
void setRotation(const Vector3 &axis, const tfScalar &angle)
Set the rotation using axis angle notation.
TFSIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q2) const
Return the difference between this quaternion and the other.
Quaternion & operator/=(const tfScalar &s)
Inversely scale this quaternion.
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...
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
TFSIMD_FORCE_INLINE tfScalar tfPow(tfScalar x, tfScalar y)
TFSIMD_FORCE_INLINE Quaternion operator-() const
Return the negative of this quaternion This simply negates each element.
tfScalar getAngle() const
Return the angle [0, 2Pi] of rotation represented by this quaternion.
tfScalar dot(const Quaternion &q) const
Return the dot product between this quaternion and another.
ROS_DEPRECATED Quaternion(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
Constructor from Euler angles.
Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte...
Quaternion(const Vector3 &axis, const tfScalar &angle)
Axis angle Constructor.
tfScalar getAngleShortestPath() const
Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path.
Quaternion(const tfScalar &x, const tfScalar &y, const tfScalar &z, const tfScalar &w)
Constructor from scalars.
Quaternion & operator-=(const Quaternion &q)
Sutfract out a quaternion.
const TFSIMD_FORCE_INLINE tfScalar & getW() const
Quaternion & operator*=(const Quaternion &q)
Multiply this quaternion by q on the right.
TFSIMD_FORCE_INLINE Quaternion farthest(const Quaternion &qd) const
TFSIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
Return the length of a quaternion.
tfScalar length2() const
Return the length squared of the quaternion.
double tfScalar
The tfScalar type abstracts floating point numbers, to easily switch between double and single floati...
Quaternion & operator*=(const tfScalar &s)
Scale this quaternion.
tfScalar angle(const Quaternion &q) const
Return the half angle between this quaternion and the other.
void setEuler(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
Set the quaternion using Euler angles.
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
Return the inverse of a quaternion.
ROS_DEPRECATED void setEulerZYX(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
Set the quaternion using euler angles.
Vector3 getAxis() const
Return the axis of the rotation represented by this quaternion.
TFSIMD_FORCE_INLINE tfScalar tfCos(tfScalar x)
TFSIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
TFSIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2(Vector3 &v0, Vector3 &v1)
Quaternion operator/(const tfScalar &s) const
Return an inversely scaled versionof this quaternion.
tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:07