19 #pragma GCC optimize("O3") 36 m.
a.
x = 1.0f-2.0f*(q3q3 + q4q4);
37 m.
a.
y = 2.0f*(q2q3 - q1q4);
38 m.
a.
z = 2.0f*(q2q4 + q1q3);
39 m.
b.
x = 2.0f*(q2q3 + q1q4);
40 m.
b.
y = 1.0f-2.0f*(q2q2 + q4q4);
41 m.
b.
z = 2.0f*(q3q4 - q1q2);
42 m.
c.
x = 2.0f*(q2q4 - q1q3);
43 m.
c.
y = 2.0f*(q3q4 + q1q2);
44 m.
c.
z = 1.0f-2.0f*(q2q2 + q3q3);
60 float invs = 1.0f / (q1q1 + q2q2 + q3q3 + q4q4);
62 m.
a.
x = ( q2q2 - q3q3 - q4q4 + q1q1)*invs;
63 m.
a.
y = 2.0f*(q2q3 - q1q4)*invs;
64 m.
a.
z = 2.0f*(q2q4 + q1q3)*invs;
65 m.
b.
x = 2.0f*(q2q3 + q1q4)*invs;
66 m.
b.
y = (-q2q2 + q3q3 - q4q4 + q1q1)*invs;
67 m.
b.
z = 2.0f*(q3q4 - q1q2)*invs;
68 m.
c.
x = 2.0f*(q2q4 - q1q3)*invs;
69 m.
c.
y = 2.0f*(q3q4 + q1q2)*invs;
70 m.
c.
z = (-q2q2 - q3q3 + q4q4 + q1q1)*invs;
78 const float &m00 = m.
a.
x;
79 const float &m11 = m.
b.
y;
80 const float &m22 = m.
c.
z;
81 const float &m10 = m.
b.
x;
82 const float &m01 = m.
a.
y;
83 const float &m20 = m.
c.
x;
84 const float &m02 = m.
a.
z;
85 const float &m21 = m.
c.
y;
86 const float &m12 = m.
b.
z;
92 float tr = m00 + m11 + m22;
95 float S = sqrtf(tr+1) * 2;
100 }
else if ((m00 > m11) && (m00 > m22)) {
101 float S = sqrtf(1.0
f + m00 - m11 - m22) * 2.0f;
102 qw = (m21 - m12) / S;
104 qy = (m01 + m10) / S;
105 qz = (m02 + m20) / S;
106 }
else if (m11 > m22) {
107 float S = sqrtf(1.0
f + m11 - m00 - m22) * 2.0f;
108 qw = (m02 - m20) / S;
109 qx = (m01 + m10) / S;
111 qz = (m12 + m21) / S;
113 float S = sqrtf(1.0
f + m22 - m00 - m11) * 2.0f;
114 qw = (m10 - m01) / S;
115 qx = (m02 + m20) / S;
116 qy = (m12 + m21) / S;
132 float cr2 = cosf(roll*0.5
f);
133 float cp2 = cosf(pitch*0.5f);
134 float cy2 = cosf(yaw*0.5f);
135 float sr2 = sinf(roll*0.5f);
136 float sp2 = sinf(pitch*0.5f);
137 float sy2 = sinf(yaw*0.5f);
139 q1 = cr2*cp2*cy2 + sr2*sp2*sy2;
140 q2 = sr2*cp2*cy2 - cr2*sp2*sy2;
141 q3 = cr2*sp2*cy2 + sr2*cp2*sy2;
142 q4 = cr2*cp2*sy2 - sr2*sp2*cy2;
174 float st2 = sinf(theta/2.0
f);
176 q1 = cosf(theta/2.0
f);
213 float t2 = theta/2.0f;
215 float st2 = t2-sqt2*t2/6.0f;
217 q1 = 1.0f-(sqt2/2.0f)+
sq(sqt2)/24.0f;
229 float t2 = theta/2.0f;
231 float st2 = t2-sqt2*t2/6.0f;
235 float w2 = 1.0f-(sqt2/2.0f)+
sq(sqt2)/24.0f;
236 float x2 = v.
x * st2;
237 float y2 = v.
y * st2;
238 float z2 = v.
z * st2;
247 q1 = w1*w2 - x1*x2 - y1*y2 - z1*z2;
248 q2 = w1*x2 + x1*w2 + y1*z2 - z1*y2;
249 q3 = w1*y2 - x1*z2 + y1*w2 + z1*x2;
250 q4 = w1*z2 + x1*y2 - y1*x2 + z1*w2;
301 float quatMagInv = 1.0f/quatMag;
312 const float &w1 =
q1;
313 const float &x1 =
q2;
314 const float &y1 =
q3;
315 const float &z1 =
q4;
322 ret.
q1 = w1*w2 - x1*x2 - y1*y2 - z1*z2;
323 ret.
q2 = w1*x2 + x1*w2 + y1*z2 - z1*y2;
324 ret.
q3 = w1*y2 - x1*z2 + y1*w2 + z1*x2;
325 ret.
q4 = w1*z2 + x1*y2 - y1*x2 + z1*w2;
342 q1 = w1*w2 - x1*x2 - y1*y2 - z1*z2;
343 q2 = w1*x2 + x1*w2 + y1*z2 - z1*y2;
344 q3 = w1*y2 - x1*z2 + y1*w2 + z1*x2;
345 q4 = w1*z2 + x1*y2 - y1*x2 + z1*w2;
353 const float &quat0 =
q1;
354 const float &quat1 =
q2;
355 const float &quat2 =
q3;
356 const float &quat3 =
q4;
363 ret.
q1 = (rquat0*quat0 + rquat1*quat1 + rquat2*quat2 + rquat3*quat3);
364 ret.
q2 = (rquat0*quat1 - rquat1*quat0 - rquat2*quat3 + rquat3*quat2);
365 ret.
q3 = (rquat0*quat2 + rquat1*quat3 - rquat2*quat0 - rquat3*quat1);
366 ret.
q4 = (rquat0*quat3 - rquat1*quat2 + rquat2*quat1 - rquat3*quat0);
void to_euler(float &roll, float &pitch, float &yaw) const
Quaternion operator/(const Quaternion &v) const
float get_euler_yaw() const
Vector3< float > Vector3f
void to_axis_angle(Vector3f &v)
void from_vector312(float roll, float pitch, float yaw)
void from_euler(float roll, float pitch, float yaw)
Quaternion & operator*=(const Quaternion &v)
Quaternion operator*(const Quaternion &v) const
void from_rotation_matrix(const Matrix3f &m)
float get_euler_roll() const
float get_euler_pitch() const
float wrap_PI(const T radian)
bool is_zero(const T fVal1)
Vector3< T > to_euler312() const
void rotation_matrix(Matrix3f &m) const
void from_axis_angle(Vector3f v)
float safe_asin(const T v)
void from_axis_angle_fast(Vector3f v)
void from_euler312(float roll, float pitch, float yaw)
Vector3f to_vector312(void) const
Quaternion inverse(void) const
void rotate(const Vector3f &v)
void earth_to_body(Vector3f &v) const
void rotation_matrix_norm(Matrix3f &m) const
void rotate_fast(const Vector3f &v)