APM:Libraries
matrix_alg.cpp
Go to the documentation of this file.
1 /*
2  * matrix3.cpp
3  * Copyright (C) Siddharth Bharat Purohit, 3DRobotics Inc. 2015
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 #pragma GCC optimize("O3")
19 
20 #include <AP_HAL/AP_HAL.h>
21 
22 #include <stdio.h>
23 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
24 #include <fenv.h>
25 #endif
26 
27 #include <AP_Math/AP_Math.h>
28 
29 extern const AP_HAL::HAL& hal;
30 
31 //TODO: use higher precision datatypes to achieve more accuracy for matrix algebra operations
32 
33 /*
34  * Does matrix multiplication of two regular/square matrices
35  *
36  * @param A, Matrix A
37  * @param B, Matrix B
38  * @param n, dimemsion of square matrices
39  * @returns multiplied matrix i.e. A*B
40  */
41 
42 float* mat_mul(float *A, float *B, uint8_t n)
43 {
44  float* ret = new float[n*n];
45  memset(ret,0.0f,n*n*sizeof(float));
46 
47  for(uint8_t i = 0; i < n; i++) {
48  for(uint8_t j = 0; j < n; j++) {
49  for(uint8_t k = 0;k < n; k++) {
50  ret[i*n + j] += A[i*n + k] * B[k*n + j];
51  }
52  }
53  }
54  return ret;
55 }
56 
57 static inline void swap(float &a, float &b)
58 {
59  float c;
60  c = a;
61  a = b;
62  b = c;
63 }
64 
65 /*
66  * calculates pivot matrix such that all the larger elements in the row are on diagonal
67  *
68  * @param A, input matrix matrix
69  * @param pivot
70  * @param n, dimenstion of square matrix
71  * @returns false = matrix is Singular or non positive definite, true = matrix inversion successful
72  */
73 
74 static void mat_pivot(float* A, float* pivot, uint8_t n)
75 {
76  for(uint8_t i = 0;i<n;i++){
77  for(uint8_t j=0;j<n;j++) {
78  pivot[i*n+j] = static_cast<float>(i==j);
79  }
80  }
81 
82  for(uint8_t i = 0;i < n; i++) {
83  uint8_t max_j = i;
84  for(uint8_t j=i;j<n;j++){
85  if(fabsf(A[j*n + i]) > fabsf(A[max_j*n + i])) {
86  max_j = j;
87  }
88  }
89 
90  if(max_j != i) {
91  for(uint8_t k = 0; k < n; k++) {
92  swap(pivot[i*n + k], pivot[max_j*n + k]);
93  }
94  }
95  }
96 }
97 
98 /*
99  * calculates matrix inverse of Lower trangular matrix using forward substitution
100  *
101  * @param L, lower triangular matrix
102  * @param out, Output inverted lower triangular matrix
103  * @param n, dimension of matrix
104  */
105 
106 static void mat_forward_sub(float *L, float *out, uint8_t n)
107 {
108  // Forward substitution solve LY = I
109  for(int i = 0; i < n; i++) {
110  out[i*n + i] = 1/L[i*n + i];
111  for (int j = i+1; j < n; j++) {
112  for (int k = i; k < j; k++) {
113  out[j*n + i] -= L[j*n + k] * out[k*n + i];
114  }
115  out[j*n + i] /= L[j*n + j];
116  }
117  }
118 }
119 
120 /*
121  * calculates matrix inverse of Upper trangular matrix using backward substitution
122  *
123  * @param U, upper triangular matrix
124  * @param out, Output inverted upper triangular matrix
125  * @param n, dimension of matrix
126  */
127 
128 static void mat_back_sub(float *U, float *out, uint8_t n)
129 {
130  // Backward Substitution solve UY = I
131  for(int i = n-1; i >= 0; i--) {
132  out[i*n + i] = 1/U[i*n + i];
133  for (int j = i - 1; j >= 0; j--) {
134  for (int k = i; k > j; k--) {
135  out[j*n + i] -= U[j*n + k] * out[k*n + i];
136  }
137  out[j*n + i] /= U[j*n + j];
138  }
139  }
140 }
141 
142 /*
143  * Decomposes square matrix into Lower and Upper triangular matrices such that
144  * A*P = L*U, where P is the pivot matrix
145  * ref: http://rosettacode.org/wiki/LU_decomposition
146  * @param U, upper triangular matrix
147  * @param out, Output inverted upper triangular matrix
148  * @param n, dimension of matrix
149  */
150 
151 static void mat_LU_decompose(float* A, float* L, float* U, float *P, uint8_t n)
152 {
153  memset(L,0,n*n*sizeof(float));
154  memset(U,0,n*n*sizeof(float));
155  memset(P,0,n*n*sizeof(float));
156  mat_pivot(A,P,n);
157 
158  float *APrime = mat_mul(P,A,n);
159  for(uint8_t i = 0; i < n; i++) {
160  L[i*n + i] = 1;
161  }
162  for(uint8_t i = 0; i < n; i++) {
163  for(uint8_t j = 0; j < n; j++) {
164  if(j <= i) {
165  U[j*n + i] = APrime[j*n + i];
166  for(uint8_t k = 0; k < j; k++) {
167  U[j*n + i] -= L[j*n + k] * U[k*n + i];
168  }
169  }
170  if(j >= i) {
171  L[j*n + i] = APrime[j*n + i];
172  for(uint8_t k = 0; k < i; k++) {
173  L[j*n + i] -= L[j*n + k] * U[k*n + i];
174  }
175  L[j*n + i] /= U[i*n + i];
176  }
177  }
178  }
179  delete[] APrime;
180 }
181 
182 /*
183  * matrix inverse code for any square matrix using LU decomposition
184  * inv = inv(U)*inv(L)*P, where L and U are triagular matrices and P the pivot matrix
185  * ref: http://www.cl.cam.ac.uk/teaching/1314/NumMethods/supporting/mcmaster-kiruba-ludecomp.pdf
186  * @param m, input 4x4 matrix
187  * @param inv, Output inverted 4x4 matrix
188  * @param n, dimension of square matrix
189  * @returns false = matrix is Singular, true = matrix inversion successful
190  */
191 static bool mat_inverse(float* A, float* inv, uint8_t n)
192 {
193  float *L, *U, *P;
194  bool ret = true;
195  L = new float[n*n];
196  U = new float[n*n];
197  P = new float[n*n];
198  mat_LU_decompose(A,L,U,P,n);
199 
200  float *L_inv = new float[n*n];
201  float *U_inv = new float[n*n];
202 
203  memset(L_inv,0,n*n*sizeof(float));
204  mat_forward_sub(L,L_inv,n);
205 
206  memset(U_inv,0,n*n*sizeof(float));
207  mat_back_sub(U,U_inv,n);
208 
209  // decomposed matrices no longer required
210  delete[] L;
211  delete[] U;
212 
213  float *inv_unpivoted = mat_mul(U_inv,L_inv,n);
214  float *inv_pivoted = mat_mul(inv_unpivoted, P, n);
215 
216  //check sanity of results
217  for(uint8_t i = 0; i < n; i++) {
218  for(uint8_t j = 0; j < n; j++) {
219  if(isnan(inv_pivoted[i*n+j]) || isinf(inv_pivoted[i*n+j])){
220  ret = false;
221  }
222  }
223  }
224  memcpy(inv,inv_pivoted,n*n*sizeof(float));
225 
226  //free memory
227  delete[] inv_pivoted;
228  delete[] inv_unpivoted;
229  delete[] P;
230  delete[] U_inv;
231  delete[] L_inv;
232  return ret;
233 }
234 
235 /*
236  * fast matrix inverse code only for 3x3 square matrix
237  *
238  * @param m, input 4x4 matrix
239  * @param invOut, Output inverted 4x4 matrix
240  * @returns false = matrix is Singular, true = matrix inversion successful
241  */
242 
243 bool inverse3x3(float m[], float invOut[])
244 {
245  float inv[9];
246  // computes the inverse of a matrix m
247  float det = m[0] * (m[4] * m[8] - m[7] * m[5]) -
248  m[1] * (m[3] * m[8] - m[5] * m[6]) +
249  m[2] * (m[3] * m[7] - m[4] * m[6]);
250  if (is_zero(det) || isinf(det)) {
251  return false;
252  }
253 
254  float invdet = 1 / det;
255 
256  inv[0] = (m[4] * m[8] - m[7] * m[5]) * invdet;
257  inv[1] = (m[2] * m[7] - m[1] * m[8]) * invdet;
258  inv[2] = (m[1] * m[5] - m[2] * m[4]) * invdet;
259  inv[3] = (m[5] * m[6] - m[3] * m[8]) * invdet;
260  inv[4] = (m[0] * m[8] - m[2] * m[6]) * invdet;
261  inv[5] = (m[3] * m[2] - m[0] * m[5]) * invdet;
262  inv[6] = (m[3] * m[7] - m[6] * m[4]) * invdet;
263  inv[7] = (m[6] * m[1] - m[0] * m[7]) * invdet;
264  inv[8] = (m[0] * m[4] - m[3] * m[1]) * invdet;
265 
266  for(uint8_t i = 0; i < 9; i++){
267  invOut[i] = inv[i];
268  }
269 
270  return true;
271 }
272 
273 /*
274  * fast matrix inverse code only for 4x4 square matrix copied from
275  * gluInvertMatrix implementation in opengl for 4x4 matrices.
276  *
277  * @param m, input 4x4 matrix
278  * @param invOut, Output inverted 4x4 matrix
279  * @returns false = matrix is Singular, true = matrix inversion successful
280  */
281 
282 bool inverse4x4(float m[],float invOut[])
283 {
284  float inv[16], det;
285  uint8_t i;
286 
287 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
288  int old = fedisableexcept(FE_OVERFLOW);
289  if (old < 0) {
290  hal.console->printf("inverse4x4(): warning: error on disabling FE_OVERFLOW floating point exception\n");
291  }
292 #endif
293 
294  inv[0] = m[5] * m[10] * m[15] -
295  m[5] * m[11] * m[14] -
296  m[9] * m[6] * m[15] +
297  m[9] * m[7] * m[14] +
298  m[13] * m[6] * m[11] -
299  m[13] * m[7] * m[10];
300 
301  inv[4] = -m[4] * m[10] * m[15] +
302  m[4] * m[11] * m[14] +
303  m[8] * m[6] * m[15] -
304  m[8] * m[7] * m[14] -
305  m[12] * m[6] * m[11] +
306  m[12] * m[7] * m[10];
307 
308  inv[8] = m[4] * m[9] * m[15] -
309  m[4] * m[11] * m[13] -
310  m[8] * m[5] * m[15] +
311  m[8] * m[7] * m[13] +
312  m[12] * m[5] * m[11] -
313  m[12] * m[7] * m[9];
314 
315  inv[12] = -m[4] * m[9] * m[14] +
316  m[4] * m[10] * m[13] +
317  m[8] * m[5] * m[14] -
318  m[8] * m[6] * m[13] -
319  m[12] * m[5] * m[10] +
320  m[12] * m[6] * m[9];
321 
322  inv[1] = -m[1] * m[10] * m[15] +
323  m[1] * m[11] * m[14] +
324  m[9] * m[2] * m[15] -
325  m[9] * m[3] * m[14] -
326  m[13] * m[2] * m[11] +
327  m[13] * m[3] * m[10];
328 
329  inv[5] = m[0] * m[10] * m[15] -
330  m[0] * m[11] * m[14] -
331  m[8] * m[2] * m[15] +
332  m[8] * m[3] * m[14] +
333  m[12] * m[2] * m[11] -
334  m[12] * m[3] * m[10];
335 
336  inv[9] = -m[0] * m[9] * m[15] +
337  m[0] * m[11] * m[13] +
338  m[8] * m[1] * m[15] -
339  m[8] * m[3] * m[13] -
340  m[12] * m[1] * m[11] +
341  m[12] * m[3] * m[9];
342 
343  inv[13] = m[0] * m[9] * m[14] -
344  m[0] * m[10] * m[13] -
345  m[8] * m[1] * m[14] +
346  m[8] * m[2] * m[13] +
347  m[12] * m[1] * m[10] -
348  m[12] * m[2] * m[9];
349 
350  inv[2] = m[1] * m[6] * m[15] -
351  m[1] * m[7] * m[14] -
352  m[5] * m[2] * m[15] +
353  m[5] * m[3] * m[14] +
354  m[13] * m[2] * m[7] -
355  m[13] * m[3] * m[6];
356 
357  inv[6] = -m[0] * m[6] * m[15] +
358  m[0] * m[7] * m[14] +
359  m[4] * m[2] * m[15] -
360  m[4] * m[3] * m[14] -
361  m[12] * m[2] * m[7] +
362  m[12] * m[3] * m[6];
363 
364  inv[10] = m[0] * m[5] * m[15] -
365  m[0] * m[7] * m[13] -
366  m[4] * m[1] * m[15] +
367  m[4] * m[3] * m[13] +
368  m[12] * m[1] * m[7] -
369  m[12] * m[3] * m[5];
370 
371  inv[14] = -m[0] * m[5] * m[14] +
372  m[0] * m[6] * m[13] +
373  m[4] * m[1] * m[14] -
374  m[4] * m[2] * m[13] -
375  m[12] * m[1] * m[6] +
376  m[12] * m[2] * m[5];
377 
378  inv[3] = -m[1] * m[6] * m[11] +
379  m[1] * m[7] * m[10] +
380  m[5] * m[2] * m[11] -
381  m[5] * m[3] * m[10] -
382  m[9] * m[2] * m[7] +
383  m[9] * m[3] * m[6];
384 
385  inv[7] = m[0] * m[6] * m[11] -
386  m[0] * m[7] * m[10] -
387  m[4] * m[2] * m[11] +
388  m[4] * m[3] * m[10] +
389  m[8] * m[2] * m[7] -
390  m[8] * m[3] * m[6];
391 
392  inv[11] = -m[0] * m[5] * m[11] +
393  m[0] * m[7] * m[9] +
394  m[4] * m[1] * m[11] -
395  m[4] * m[3] * m[9] -
396  m[8] * m[1] * m[7] +
397  m[8] * m[3] * m[5];
398 
399  inv[15] = m[0] * m[5] * m[10] -
400  m[0] * m[6] * m[9] -
401  m[4] * m[1] * m[10] +
402  m[4] * m[2] * m[9] +
403  m[8] * m[1] * m[6] -
404  m[8] * m[2] * m[5];
405 
406  det = m[0] * inv[0] + m[1] * inv[4] + m[2] * inv[8] + m[3] * inv[12];
407 
408 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
409  if (old >= 0 && feenableexcept(old) < 0) {
410  hal.console->printf("inverse4x4(): warning: error on restoring floating exception mask\n");
411  }
412 #endif
413 
414  if (is_zero(det) || isinf(det)){
415  return false;
416  }
417 
418  det = 1.0f / det;
419 
420  for (i = 0; i < 16; i++)
421  invOut[i] = inv[i] * det;
422  return true;
423 }
424 
425 /*
426  * generic matrix inverse code
427  *
428  * @param x, input nxn matrix
429  * @param y, Output inverted nxn matrix
430  * @param n, dimension of square matrix
431  * @returns false = matrix is Singular, true = matrix inversion successful
432  */
433 bool inverse(float x[], float y[], uint16_t dim)
434 {
435  switch(dim){
436  case 3: return inverse3x3(x,y);
437  case 4: return inverse4x4(x,y);
438  default: return mat_inverse(x,y,dim);
439  }
440 }
float * mat_mul(float *A, float *B, uint8_t n)
Definition: matrix_alg.cpp:42
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static void swap(float &a, float &b)
Definition: matrix_alg.cpp:57
static void mat_pivot(float *A, float *pivot, uint8_t n)
Definition: matrix_alg.cpp:74
bool inverse3x3(float m[], float invOut[])
Definition: matrix_alg.cpp:243
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: matrix_alg.cpp:8
#define x(i)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool inverse(float x[], float y[], uint16_t dim)
Definition: matrix_alg.cpp:433
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
static bool mat_inverse(float *A, float *inv, uint8_t n)
Definition: matrix_alg.cpp:191
static void mat_back_sub(float *U, float *out, uint8_t n)
Definition: matrix_alg.cpp:128
bool inverse4x4(float m[], float invOut[])
Definition: matrix_alg.cpp:282
static void mat_LU_decompose(float *A, float *L, float *U, float *P, uint8_t n)
Definition: matrix_alg.cpp:151
static void mat_forward_sub(float *L, float *out, uint8_t n)
Definition: matrix_alg.cpp:106