APM:Libraries
matrix3.cpp
Go to the documentation of this file.
1 /*
2  * matrix3.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 // create a rotation matrix given some euler angles
24 // this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf
25 template <typename T>
26 void Matrix3<T>::from_euler(float roll, float pitch, float yaw)
27 {
28  float cp = cosf(pitch);
29  float sp = sinf(pitch);
30  float sr = sinf(roll);
31  float cr = cosf(roll);
32  float sy = sinf(yaw);
33  float cy = cosf(yaw);
34 
35  a.x = cp * cy;
36  a.y = (sr * sp * cy) - (cr * sy);
37  a.z = (cr * sp * cy) + (sr * sy);
38  b.x = cp * sy;
39  b.y = (sr * sp * sy) + (cr * cy);
40  b.z = (cr * sp * sy) - (sr * cy);
41  c.x = -sp;
42  c.y = sr * cp;
43  c.z = cr * cp;
44 }
45 
46 // calculate euler angles from a rotation matrix
47 // this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf
48 template <typename T>
49 void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw) const
50 {
51  if (pitch != nullptr) {
52  *pitch = -safe_asin(c.x);
53  }
54  if (roll != nullptr) {
55  *roll = atan2f(c.y, c.z);
56  }
57  if (yaw != nullptr) {
58  *yaw = atan2f(b.x, a.x);
59  }
60 }
61 
62 template <typename T>
64 {
65  (*this).a(1,0,0);
66  (*this).b(0,1,0);
67  (*this).c(0,0,1);
68 
69  (*this).a.rotate(rotation);
70  (*this).b.rotate(rotation);
71  (*this).c.rotate(rotation);
72  (*this).transpose();
73 }
74 
75 /*
76  calculate Euler angles (312 convention) for the matrix.
77  See http://www.atacolorado.com/eulersequences.doc
78  vector is returned in r, p, y order
79 */
80 template <typename T>
82 {
83  return Vector3<T>(asinf(c.y),
84  atan2f(-c.x, c.z),
85  atan2f(-a.y, b.y));
86 }
87 
88 /*
89  fill the matrix from Euler angles in radians in 312 convention
90 */
91 template <typename T>
92 void Matrix3<T>::from_euler312(float roll, float pitch, float yaw)
93 {
94  float c3 = cosf(pitch);
95  float s3 = sinf(pitch);
96  float s2 = sinf(roll);
97  float c2 = cosf(roll);
98  float s1 = sinf(yaw);
99  float c1 = cosf(yaw);
100 
101  a.x = c1 * c3 - s1 * s2 * s3;
102  b.y = c1 * c2;
103  c.z = c3 * c2;
104  a.y = -c2*s1;
105  a.z = s3*c1 + c3*s2*s1;
106  b.x = c3*s1 + s3*s2*c1;
107  b.z = s1*s3 - s2*c1*c3;
108  c.x = -s3*c2;
109  c.y = s2;
110 }
111 
112 // apply an additional rotation from a body frame gyro vector
113 // to a rotation matrix.
114 template <typename T>
116 {
117  Matrix3<T> temp_matrix;
118  temp_matrix.a.x = a.y * g.z - a.z * g.y;
119  temp_matrix.a.y = a.z * g.x - a.x * g.z;
120  temp_matrix.a.z = a.x * g.y - a.y * g.x;
121  temp_matrix.b.x = b.y * g.z - b.z * g.y;
122  temp_matrix.b.y = b.z * g.x - b.x * g.z;
123  temp_matrix.b.z = b.x * g.y - b.y * g.x;
124  temp_matrix.c.x = c.y * g.z - c.z * g.y;
125  temp_matrix.c.y = c.z * g.x - c.x * g.z;
126  temp_matrix.c.z = c.x * g.y - c.y * g.x;
127 
128  (*this) += temp_matrix;
129 }
130 
131 /*
132  re-normalise a rotation matrix
133 */
134 template <typename T>
136 {
137  float error = a * b;
138  Vector3<T> t0 = a - (b * (0.5f * error));
139  Vector3<T> t1 = b - (a * (0.5f * error));
140  Vector3<T> t2 = t0 % t1;
141  a = t0 * (1.0f / t0.length());
142  b = t1 * (1.0f / t1.length());
143  c = t2 * (1.0f / t2.length());
144 }
145 
146 // multiplication by a vector
147 template <typename T>
149 {
150  return Vector3<T>(a.x * v.x + a.y * v.y + a.z * v.z,
151  b.x * v.x + b.y * v.y + b.z * v.z,
152  c.x * v.x + c.y * v.y + c.z * v.z);
153 }
154 
155 // multiplication by a vector, extracting only the xy components
156 template <typename T>
158 {
159  return Vector2<T>(a.x * v.x + a.y * v.y + a.z * v.z,
160  b.x * v.x + b.y * v.y + b.z * v.z);
161 }
162 
163 // multiplication of transpose by a vector
164 template <typename T>
166 {
167  return Vector3<T>(a.x * v.x + b.x * v.y + c.x * v.z,
168  a.y * v.x + b.y * v.y + c.y * v.z,
169  a.z * v.x + b.z * v.y + c.z * v.z);
170 }
171 
172 // multiplication by another Matrix3<T>
173 template <typename T>
175 {
176  Matrix3<T> temp (Vector3<T>(a.x * m.a.x + a.y * m.b.x + a.z * m.c.x,
177  a.x * m.a.y + a.y * m.b.y + a.z * m.c.y,
178  a.x * m.a.z + a.y * m.b.z + a.z * m.c.z),
179  Vector3<T>(b.x * m.a.x + b.y * m.b.x + b.z * m.c.x,
180  b.x * m.a.y + b.y * m.b.y + b.z * m.c.y,
181  b.x * m.a.z + b.y * m.b.z + b.z * m.c.z),
182  Vector3<T>(c.x * m.a.x + c.y * m.b.x + c.z * m.c.x,
183  c.x * m.a.y + c.y * m.b.y + c.z * m.c.y,
184  c.x * m.a.z + c.y * m.b.z + c.z * m.c.z));
185  return temp;
186 }
187 
188 template <typename T>
190 {
191  return Matrix3<T>(Vector3<T>(a.x, b.x, c.x),
192  Vector3<T>(a.y, b.y, c.y),
193  Vector3<T>(a.z, b.z, c.z));
194 }
195 
196 template <typename T>
198 {
199  return a.x * (b.y * c.z - b.z * c.y) +
200  a.y * (b.z * c.x - b.x * c.z) +
201  a.z * (b.x * c.y - b.y * c.x);
202 }
203 
204 template <typename T>
206 {
207  T d = det();
208 
209  if (is_zero(d)) {
210  return false;
211  }
212 
213  inv.a.x = (b.y * c.z - c.y * b.z) / d;
214  inv.a.y = (a.z * c.y - a.y * c.z) / d;
215  inv.a.z = (a.y * b.z - a.z * b.y) / d;
216  inv.b.x = (b.z * c.x - b.x * c.z) / d;
217  inv.b.y = (a.x * c.z - a.z * c.x) / d;
218  inv.b.z = (b.x * a.z - a.x * b.z) / d;
219  inv.c.x = (b.x * c.y - c.x * b.y) / d;
220  inv.c.y = (c.x * a.y - a.x * c.y) / d;
221  inv.c.z = (a.x * b.y - b.x * a.y) / d;
222 
223  return true;
224 }
225 
226 template <typename T>
228 {
229  Matrix3<T> inv;
230  bool success = inverse(inv);
231  if (success) {
232  *this = inv;
233  }
234  return success;
235 }
236 
237 template <typename T>
239 {
240  a.x = a.y = a.z = 0;
241  b.x = b.y = b.z = 0;
242  c.x = c.y = c.z = 0;
243 }
244 
245 // create rotation matrix for rotation about the vector v by angle theta
246 // See: http://www.euclideanspace.com/maths/geometry/rotations/conversions/angleToMatrix/
247 template <typename T>
248 void Matrix3<T>::from_axis_angle(const Vector3<T> &v, float theta)
249 {
250  float C = cosf(theta);
251  float S = sinf(theta);
252  float t = 1.0f - C;
253  Vector3f normv = v.normalized();
254  float x = normv.x;
255  float y = normv.y;
256  float z = normv.z;
257 
258  a.x = t*x*x + C;
259  a.y = t*x*y - z*S;
260  a.z = t*x*z + y*S;
261  b.x = t*x*y + z*S;
262  b.y = t*y*y + C;
263  b.z = t*y*z - x*S;
264  c.x = t*x*z - y*S;
265  c.y = t*y*z + x*S;
266  c.z = t*z*z + C;
267 }
268 
269 
270 // only define for float
271 template void Matrix3<float>::zero(void);
272 template void Matrix3<float>::rotate(const Vector3<float> &g);
273 template void Matrix3<float>::normalize(void);
274 template void Matrix3<float>::from_euler(float roll, float pitch, float yaw);
275 template void Matrix3<float>::to_euler(float *roll, float *pitch, float *yaw) const;
276 template void Matrix3<float>::from_rotation(enum Rotation rotation);
277 template void Matrix3<float>::from_euler312(float roll, float pitch, float yaw);
278 template void Matrix3<float>::from_axis_angle(const Vector3<float> &v, float theta);
279 template Vector3<float> Matrix3<float>::to_euler312(void) const;
283 template Matrix3<float> Matrix3<float>::transposed(void) const;
284 template float Matrix3<float>::det() const;
285 template bool Matrix3<float>::inverse(Matrix3<float>& inv) const;
286 template bool Matrix3<float>::invert();
287 template Vector2<float> Matrix3<float>::mulXY(const Vector3<float> &v) const;
288 
289 template void Matrix3<double>::zero(void);
290 template void Matrix3<double>::rotate(const Vector3<double> &g);
291 template void Matrix3<double>::from_euler(float roll, float pitch, float yaw);
292 template void Matrix3<double>::to_euler(float *roll, float *pitch, float *yaw) const;
296 template Matrix3<double> Matrix3<double>::transposed(void) const;
297 template double Matrix3<double>::det() const;
298 template bool Matrix3<double>::inverse(Matrix3<double>& inv) const;
299 template bool Matrix3<double>::invert();
t2
Definition: calcH_MAG.c:1
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
Vector3< T > normalized() const
Definition: vector3.h:188
Vector2< T > mulXY(const Vector3< T > &v) const
Definition: matrix3.cpp:157
void from_axis_angle(const Vector3< T > &v, float theta)
Definition: matrix3.cpp:248
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
Rotation
Definition: rotations.h:27
t0
Definition: calcTms.c:1
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
#define x(i)
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
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 from_rotation(enum Rotation rotation)
Definition: matrix3.cpp:63
Matrix3< T > operator*(const T num) const
Definition: matrix3.h:113
float v
Definition: Printf.cpp:15
float safe_asin(const T v)
Definition: AP_Math.cpp:43
float length(void) const
Definition: vector3.cpp:288
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
void zero(void)
Definition: matrix3.cpp:238
void from_euler312(float roll, float pitch, float yaw)
Definition: matrix3.cpp:92
bool invert()
Definition: matrix3.cpp:227
bool inverse(float x[], float y[], uint16_t dim)
Definition: matrix_alg.cpp:433
#define error(fmt, args ...)
T det() const
Definition: matrix3.cpp:197
bool inverse(Matrix3< T > &inv) const
Definition: matrix3.cpp:205
Vector3< T > b
Definition: matrix3.h:48
void rotate(const Vector3< T > &g)
Definition: matrix3.cpp:115
void normalize(void)
Definition: matrix3.cpp:135
Vector3< T > a
Definition: matrix3.h:48
T x
Definition: vector3.h:67