Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- |
2 | /* |
||
3 | * quaternion.cpp |
||
4 | * Copyright (C) Andrew Tridgell 2012 |
||
5 | * |
||
6 | * This file is free software: you can redistribute it and/or modify it |
||
7 | * under the terms of the GNU General Public License as published by the |
||
8 | * Free Software Foundation, either version 3 of the License, or |
||
9 | * (at your option) any later version. |
||
10 | * |
||
11 | * This file is distributed in the hope that it will be useful, but |
||
12 | * WITHOUT ANY WARRANTY; without even the implied warranty of |
||
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
||
14 | * See the GNU General Public License for more details. |
||
15 | * |
||
16 | * You should have received a copy of the GNU General Public License along |
||
17 | * with this program. If not, see <http://www.gnu.org/licenses/>. |
||
18 | */ |
||
19 | |||
20 | #include "AP_Math.h" |
||
21 | |||
22 | // return the rotation matrix equivalent for this quaternion |
||
23 | void Quaternion::rotation_matrix(Matrix3f &m) |
||
24 | { |
||
25 | float q3q3 = q3 * q3; |
||
26 | float q3q4 = q3 * q4; |
||
27 | float q2q2 = q2 * q2; |
||
28 | float q2q3 = q2 * q3; |
||
29 | float q2q4 = q2 * q4; |
||
30 | float q1q2 = q1 * q2; |
||
31 | float q1q3 = q1 * q3; |
||
32 | float q1q4 = q1 * q4; |
||
33 | float q4q4 = q4 * q4; |
||
34 | |||
35 | m.a.x = 1-2*(q3q3 + q4q4); |
||
36 | m.a.y = 2*(q2q3 - q1q4); |
||
37 | m.a.z = 2*(q2q4 + q1q3); |
||
38 | m.b.x = 2*(q2q3 + q1q4); |
||
39 | m.b.y = 1-2*(q2q2 + q4q4); |
||
40 | m.b.z = 2*(q3q4 - q1q2); |
||
41 | m.c.x = 2*(q2q4 - q1q3); |
||
42 | m.c.y = 2*(q3q4 + q1q2); |
||
43 | m.c.z = 1-2*(q2q2 + q3q3); |
||
44 | } |
||
45 | |||
46 | // convert a vector from earth to body frame |
||
47 | void Quaternion::earth_to_body(Vector3f &v) |
||
48 | { |
||
49 | Matrix3f m; |
||
50 | // we reverse z before and afterwards because of the differing |
||
51 | // quaternion conventions from APM conventions. |
||
52 | v.z = -v.z; |
||
53 | rotation_matrix(m); |
||
54 | v = m * v; |
||
55 | v.z = -v.z; |
||
56 | } |
||
57 | |||
58 | // create a quaternion from Euler angles |
||
59 | void Quaternion::from_euler(float roll, float pitch, float yaw) |
||
60 | { |
||
61 | float cr2 = cos(roll*0.5); |
||
62 | float cp2 = cos(pitch*0.5); |
||
63 | float cy2 = cos(yaw*0.5); |
||
64 | float sr2 = sin(roll*0.5); |
||
65 | float sp2 = sin(pitch*0.5); |
||
66 | float sy2 = sin(yaw*0.5); |
||
67 | |||
68 | q1 = cr2*cp2*cy2 + sr2*sp2*sy2; |
||
69 | q2 = sr2*cp2*cy2 - cr2*sp2*sy2; |
||
70 | q3 = cr2*sp2*cy2 + sr2*cp2*sy2; |
||
71 | q4 = cr2*cp2*sy2 - sr2*sp2*cy2; |
||
72 | } |
||
73 | |||
74 | // create eulers from a quaternion |
||
75 | void Quaternion::to_euler(float *roll, float *pitch, float *yaw) |
||
76 | { |
||
77 | if (roll) { |
||
78 | *roll = (atan2(2.0*(q1*q2 + q3*q4), |
||
79 | 1 - 2.0*(q2*q2 + q3*q3))); |
||
80 | } |
||
81 | if (pitch) { |
||
82 | // we let safe_asin() handle the singularities near 90/-90 in pitch |
||
83 | *pitch = safe_asin(2.0*(q1*q3 - q4*q2)); |
||
84 | } |
||
85 | if (yaw) { |
||
86 | *yaw = atan2(2.0*(q1*q4 + q2*q3), |
||
87 | 1 - 2.0*(q3*q3 + q4*q4)); |
||
88 | } |
||
89 | } |