Go to the documentation of this file.
17 #ifndef TF2_QUATERNION_H_
18 #define TF2_QUATERNION_H_
39 : QuadWord(x, y, z, w)
54 #ifndef TF2_EULER_DEFAULT_ZYX
68 setValue(axis.x() * s, axis.y() * s, axis.z() * s,
86 setValue(cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
87 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
88 sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
89 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
106 setValue(sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw,
107 cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw,
108 cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw,
109 cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw);
123 m_floats[0] += q.x(); m_floats[1] += q.y(); m_floats[2] += q.z(); m_floats[3] += q.m_floats[3];
131 m_floats[0] -= q.x(); m_floats[1] -= q.y(); m_floats[2] -= q.z(); m_floats[3] -= q.m_floats[3];
139 m_floats[0] *= s; m_floats[1] *= s; m_floats[2] *= s; m_floats[3] *= s;
148 setValue(m_floats[3] * q.x() + m_floats[0] * q.m_floats[3] + m_floats[1] * q.z() - m_floats[2] * q.y(),
149 m_floats[3] * q.y() + m_floats[1] * q.m_floats[3] + m_floats[2] * q.x() - m_floats[0] * q.z(),
150 m_floats[3] * q.z() + m_floats[2] * q.m_floats[3] + m_floats[0] * q.y() - m_floats[1] * q.x(),
151 m_floats[3] * q.m_floats[3] - m_floats[0] * q.x() - m_floats[1] * q.y() - m_floats[2] * q.z());
158 return m_floats[0] * q.x() + m_floats[1] * q.y() + m_floats[2] * q.z() + m_floats[3] * q.m_floats[3];
185 return Quaternion(x() * s, y() * s, z() * s, m_floats[3] * s);
240 if (m_floats[3] >= 0)
253 return Vector3(1.0, 0.0, 0.0);
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());
448 Vector3 c = v0.cross(v1);
461 return Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,s * 0.5f);
TF2SIMD_FORCE_INLINE Quaternion operator+(const Quaternion &q2) const
Return the sum of this quaternion and the other.
TF2SIMD_FORCE_INLINE tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Quaternion & operator/=(const tf2Scalar &s)
Inversely scale this quaternion.
static const Quaternion & getIdentity()
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2(Vector3 &v0, Vector3 &v1)
const TF2SIMD_FORCE_INLINE tf2Scalar & getW() const
tf2Scalar getAngleShortestPath() const
Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path.
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
Set the quaternion using fixed axis RPY.
TF2SIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
Return the inverse of a quaternion.
TF2SIMD_FORCE_INLINE tf2Scalar angleShortestPath(const Quaternion &q1, const Quaternion &q2)
Return the shortest angle between two quaternions.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sin(tf2Scalar x)
ROS_DEPRECATED Quaternion(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
Constructor from Euler angles.
TF2SIMD_FORCE_INLINE Quaternion operator-() const
Return the negative of this quaternion This simply negates each element.
Quaternion & normalize()
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x)
tf2Scalar angle(const Quaternion &q) const
Return the half angle between this quaternion and the other.
Quaternion operator/(const tf2Scalar &s) const
Return an inversely scaled versionof this quaternion.
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q2) const
Return the difference between this quaternion and the other.
Quaternion()
No initialization constructor.
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...
Quaternion(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z, const tf2Scalar &w)
Constructor from scalars.
Vector3 getAxis() const
Return the axis of the rotation represented by this quaternion.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Acos(tf2Scalar x)
TF2SIMD_FORCE_INLINE Quaternion & operator+=(const Quaternion &q)
Add two quaternions.
TF2SIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
tf2Scalar getAngle() const
Return the angle [0, 2Pi] of rotation represented by this quaternion.
tf2Scalar length() const
Return the length of the quaternion.
#define TF2SIMD_FORCE_INLINE
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1(const Vector3 &n, Vector3 &p, Vector3 &q)
TF2SIMD_FORCE_INLINE Quaternion farthest(const Quaternion &qd) const
void setRotation(const Vector3 &axis, const tf2Scalar &angle)
Set the rotation using axis angle notation.
Quaternion & operator*=(const Quaternion &q)
Multiply this quaternion by q on the right.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x)
Quaternion inverse() const
Return the inverse of this quaternion.
tf2Scalar dot(const Quaternion &q) const
Return the dot product between this quaternion and another.
TF2SIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
Set the quaternion using Euler angles.
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Return the half angle between two quaternions.
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
ROS_DEPRECATED void setEulerZYX(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
Set the quaternion using euler angles.
Quaternion normalized() const
Return a normalized version of this quaternion.
TF2SIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t)
Return the result of spherical linear interpolation betwen two quaternions.
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
Return the length of a quaternion.
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
TF2SIMD_FORCE_INLINE Quaternion operator*(const tf2Scalar &s) const
Return a scaled version of this quaternion.
TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion &q)
Return the negative of a quaternion.
TF2SIMD_FORCE_INLINE Quaternion nearest(const Quaternion &qd) const
Quaternion & operator*=(const tf2Scalar &s)
Scale this quaternion.
TF2SIMD_FORCE_INLINE tf2Scalar tf2Pow(tf2Scalar x, tf2Scalar y)
Quaternion & operator-=(const Quaternion &q)
Sutf2ract out a quaternion.
tf2Scalar angleShortestPath(const Quaternion &q) const
Return the angle between this quaternion and the other along the shortest path.
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuat(const Vector3 &v0, const Vector3 &v1)
tf2Scalar length2() const
Return the length squared of the quaternion.
Quaternion(const Vector3 &axis, const tf2Scalar &angle)
Axis angle Constructor.
tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:11