APM:Libraries
quaternion.cpp
Go to the documentation of this file.
1 /*
2  * quaternion.cpp
3  * Copyright (C) Andrew Tridgell 2012
4  *
5  * This file is free software: you can redistribute it and/or modify it
6  * under the terms of the GNU General Public License as published by the
7  * Free Software Foundation, either version 3 of the License, or
8  * (at your option) any later version.
9  *
10  * This file is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13  * See the GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License along
16  * with this program. If not, see <http://www.gnu.org/licenses/>.
17  */
18 
19 #pragma GCC optimize("O3")
20 
21 #include "AP_Math.h"
22 
23 // return the rotation matrix equivalent for this quaternion
25 {
26  float q3q3 = q3 * q3;
27  float q3q4 = q3 * q4;
28  float q2q2 = q2 * q2;
29  float q2q3 = q2 * q3;
30  float q2q4 = q2 * q4;
31  float q1q2 = q1 * q2;
32  float q1q3 = q1 * q3;
33  float q1q4 = q1 * q4;
34  float q4q4 = q4 * q4;
35 
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);
45 }
46 
47 // return the rotation matrix equivalent for this quaternion after normalization
49 {
50  float q1q1 = q1 * q1;
51  float q1q2 = q1 * q2;
52  float q1q3 = q1 * q3;
53  float q1q4 = q1 * q4;
54  float q2q2 = q2 * q2;
55  float q2q3 = q2 * q3;
56  float q2q4 = q2 * q4;
57  float q3q3 = q3 * q3;
58  float q3q4 = q3 * q4;
59  float q4q4 = q4 * q4;
60  float invs = 1.0f / (q1q1 + q2q2 + q3q3 + q4q4);
61 
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;
71 }
72 
73 // return the rotation matrix equivalent for this quaternion
74 // Thanks to Martin John Baker
75 // http://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/index.htm
77 {
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;
87  float &qw = q1;
88  float &qx = q2;
89  float &qy = q3;
90  float &qz = q4;
91 
92  float tr = m00 + m11 + m22;
93 
94  if (tr > 0) {
95  float S = sqrtf(tr+1) * 2;
96  qw = 0.25f * S;
97  qx = (m21 - m12) / S;
98  qy = (m02 - m20) / S;
99  qz = (m10 - m01) / S;
100  } else if ((m00 > m11) && (m00 > m22)) {
101  float S = sqrtf(1.0f + m00 - m11 - m22) * 2.0f;
102  qw = (m21 - m12) / S;
103  qx = 0.25f * S;
104  qy = (m01 + m10) / S;
105  qz = (m02 + m20) / S;
106  } else if (m11 > m22) {
107  float S = sqrtf(1.0f + m11 - m00 - m22) * 2.0f;
108  qw = (m02 - m20) / S;
109  qx = (m01 + m10) / S;
110  qy = 0.25f * S;
111  qz = (m12 + m21) / S;
112  } else {
113  float S = sqrtf(1.0f + m22 - m00 - m11) * 2.0f;
114  qw = (m10 - m01) / S;
115  qx = (m02 + m20) / S;
116  qy = (m12 + m21) / S;
117  qz = 0.25f * S;
118  }
119 }
120 
121 // convert a vector from earth to body frame
123 {
124  Matrix3f m;
125  rotation_matrix(m);
126  v = m * v;
127 }
128 
129 // create a quaternion from Euler angles
130 void Quaternion::from_euler(float roll, float pitch, float yaw)
131 {
132  float cr2 = cosf(roll*0.5f);
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);
138 
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;
143 }
144 
145 // create a quaternion from Euler angles
146 void Quaternion::from_vector312(float roll ,float pitch, float yaw)
147 {
148  Matrix3f m;
149  m.from_euler312(roll, pitch, yaw);
150 
152 }
153 
155 {
156  float theta = v.length();
157  if (is_zero(theta)) {
158  q1 = 1.0f;
159  q2=q3=q4=0.0f;
160  return;
161  }
162  v /= theta;
163  from_axis_angle(v,theta);
164 }
165 
166 void Quaternion::from_axis_angle(const Vector3f &axis, float theta)
167 {
168  // axis must be a unit vector as there is no check for length
169  if (is_zero(theta)) {
170  q1 = 1.0f;
171  q2=q3=q4=0.0f;
172  return;
173  }
174  float st2 = sinf(theta/2.0f);
175 
176  q1 = cosf(theta/2.0f);
177  q2 = axis.x * st2;
178  q3 = axis.y * st2;
179  q4 = axis.z * st2;
180 }
181 
183 {
184  Quaternion r;
185  r.from_axis_angle(v);
186  (*this) *= r;
187 }
188 
190 {
191  float l = sqrtf(sq(q2)+sq(q3)+sq(q4));
192  v = Vector3f(q2,q3,q4);
193  if (!is_zero(l)) {
194  v /= l;
195  v *= wrap_PI(2.0f * atan2f(l,q1));
196  }
197 }
198 
200 {
201  float theta = v.length();
202  if (is_zero(theta)) {
203  q1 = 1.0f;
204  q2=q3=q4=0.0f;
205  return;
206  }
207  v /= theta;
208  from_axis_angle_fast(v,theta);
209 }
210 
211 void Quaternion::from_axis_angle_fast(const Vector3f &axis, float theta)
212 {
213  float t2 = theta/2.0f;
214  float sqt2 = sq(t2);
215  float st2 = t2-sqt2*t2/6.0f;
216 
217  q1 = 1.0f-(sqt2/2.0f)+sq(sqt2)/24.0f;
218  q2 = axis.x * st2;
219  q3 = axis.y * st2;
220  q4 = axis.z * st2;
221 }
222 
224 {
225  float theta = v.length();
226  if (is_zero(theta)) {
227  return;
228  }
229  float t2 = theta/2.0f;
230  float sqt2 = sq(t2);
231  float st2 = t2-sqt2*t2/6.0f;
232  st2 /= theta;
233 
234  //"rotation quaternion"
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;
239 
240  //copy our quaternion
241  float w1 = q1;
242  float x1 = q2;
243  float y1 = q3;
244  float z1 = q4;
245 
246  //do the multiply into our quaternion
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;
251 }
252 
253 // get euler roll angle
255 {
256  return (atan2f(2.0f*(q1*q2 + q3*q4), 1.0f - 2.0f*(q2*q2 + q3*q3)));
257 }
258 
259 // get euler pitch angle
261 {
262  return safe_asin(2.0f*(q1*q3 - q4*q2));
263 }
264 
265 // get euler yaw angle
267 {
268  return atan2f(2.0f*(q1*q4 + q2*q3), 1.0f - 2.0f*(q3*q3 + q4*q4));
269 }
270 
271 // create eulers from a quaternion
272 void Quaternion::to_euler(float &roll, float &pitch, float &yaw) const
273 {
274  roll = get_euler_roll();
275  pitch = get_euler_pitch();
276  yaw = get_euler_yaw();
277 }
278 
279 // create eulers from a quaternion
281 {
282  Matrix3f m;
283  rotation_matrix(m);
284  return m.to_euler312();
285 }
286 
287 float Quaternion::length(void) const
288 {
289  return sqrtf(sq(q1) + sq(q2) + sq(q3) + sq(q4));
290 }
291 
293 {
294  return Quaternion(q1, -q2, -q3, -q4);
295 }
296 
298 {
299  float quatMag = length();
300  if (!is_zero(quatMag)) {
301  float quatMagInv = 1.0f/quatMag;
302  q1 *= quatMagInv;
303  q2 *= quatMagInv;
304  q3 *= quatMagInv;
305  q4 *= quatMagInv;
306  }
307 }
308 
310 {
311  Quaternion ret;
312  const float &w1 = q1;
313  const float &x1 = q2;
314  const float &y1 = q3;
315  const float &z1 = q4;
316 
317  float w2 = v.q1;
318  float x2 = v.q2;
319  float y2 = v.q3;
320  float z2 = v.q4;
321 
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;
326 
327  return ret;
328 }
329 
331 {
332  float w1 = q1;
333  float x1 = q2;
334  float y1 = q3;
335  float z1 = q4;
336 
337  float w2 = v.q1;
338  float x2 = v.q2;
339  float y2 = v.q3;
340  float z2 = v.q4;
341 
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;
346 
347  return *this;
348 }
349 
351 {
352  Quaternion ret;
353  const float &quat0 = q1;
354  const float &quat1 = q2;
355  const float &quat2 = q3;
356  const float &quat3 = q4;
357 
358  float rquat0 = v.q1;
359  float rquat1 = v.q2;
360  float rquat2 = v.q3;
361  float rquat3 = v.q4;
362 
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);
367  return ret;
368 }
t2
Definition: calcH_MAG.c:1
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
Quaternion operator/(const Quaternion &v) const
Definition: quaternion.cpp:350
float get_euler_yaw() const
Definition: quaternion.cpp:266
Vector3< float > Vector3f
Definition: vector3.h:246
void to_axis_angle(Vector3f &v)
Definition: quaternion.cpp:189
void from_vector312(float roll, float pitch, float yaw)
Definition: quaternion.cpp:146
float q1
Definition: quaternion.h:27
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
Quaternion & operator*=(const Quaternion &v)
Definition: quaternion.cpp:330
Quaternion operator*(const Quaternion &v) const
Definition: quaternion.cpp:309
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
float q3
Definition: quaternion.h:27
float get_euler_roll() const
Definition: quaternion.cpp:254
float get_euler_pitch() const
Definition: quaternion.cpp:260
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
Vector3< T > to_euler312() const
Definition: matrix3.cpp:81
T z
Definition: vector3.h:67
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
float v
Definition: Printf.cpp:15
void from_axis_angle(Vector3f v)
Definition: quaternion.cpp:154
float safe_asin(const T v)
Definition: AP_Math.cpp:43
void from_axis_angle_fast(Vector3f v)
Definition: quaternion.cpp:199
float length(void) const
Definition: vector3.cpp:288
void from_euler312(float roll, float pitch, float yaw)
Definition: matrix3.cpp:92
void normalize()
Definition: quaternion.cpp:297
Vector3f to_vector312(void) const
Definition: quaternion.cpp:280
float q4
Definition: quaternion.h:27
float sq(const T val)
Definition: AP_Math.h:170
Quaternion inverse(void) const
Definition: quaternion.cpp:292
void rotate(const Vector3f &v)
Definition: quaternion.cpp:182
Vector3< T > b
Definition: matrix3.h:48
float length(void) const
Definition: quaternion.cpp:287
void earth_to_body(Vector3f &v) const
Definition: quaternion.cpp:122
Vector3< T > a
Definition: matrix3.h:48
float q2
Definition: quaternion.h:27
void rotation_matrix_norm(Matrix3f &m) const
Definition: quaternion.cpp:48
T x
Definition: vector3.h:67
void rotate_fast(const Vector3f &v)
Definition: quaternion.cpp:223