APM:Libraries
matrix_alg.cpp
Go to the documentation of this file.
1 //
2 // Unit tests for the AP_Math rotations code
3 //
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_Math/AP_Math.h>
7 #include <stdio.h>
9 
10 #define MAT_ALG_ACCURACY 1e-4f
11 
12 static uint16_t get_random(void)
13 {
14  static uint32_t m_z = 1234;
15  static uint32_t m_w = 76542;
16  m_z = 36969 * (m_z & 65535) + (m_z >> 16);
17  m_w = 18000 * (m_w & 65535) + (m_w >> 16);
18  return ((m_z << 16) + m_w) & 0xF;
19 }
20 
21 
22 static void show_matrix(float *A, int n) {
23  for (int i = 0; i < n; i++) {
24  for (int j = 0; j < n; j++)
25  printf("%.10f ", A[i * n + j]);
26  printf("\n");
27  }
28 }
29 
30 static bool compare_mat(const float *A, const float *B, const uint8_t n)
31 {
32  for(uint8_t i = 0; i < n; i++) {
33  for(uint8_t j = 0; j < n; j++) {
34  if(fabsf(A[i*n + j] - B[i*n + j]) > MAT_ALG_ACCURACY) {
35  return false;
36  }
37  }
38  }
39  return true;
40 }
41 
42 static void test_matrix_inverse(void)
43 {
44  //fast inverses
45  float test_mat[25],ident_mat[25];
46  float *out_mat;
47  for(uint8_t i = 0;i<25;i++) {
48  test_mat[i] = pow(-1,i)*get_random()/0.7f;
49  }
50  float mat[25];
51 
52 
53  //Test for 3x3 matrix
54  memset(ident_mat,0,sizeof(ident_mat));
55  for(uint8_t i=0; i<3; i++) {
56  ident_mat[i*3+i] = 1.0f;
57  }
58  if(inverse(test_mat,mat,3)){
59  out_mat = mat_mul(test_mat,mat,3);
60  inverse(mat,mat,3);
61  } else {
62  hal.console->printf("3x3 Matrix is Singular!\n");
63  return;
64 
65  }
66  printf("\n\n3x3 Test Matrix:\n");
67  show_matrix(test_mat,3);
68  printf("\nInverse of Inverse of matrix\n");
69  show_matrix(mat,3);
70  printf("\nInv(A) * A\n");
71  show_matrix(out_mat,3);
72  printf("\n");
73  //compare matrix
74  if(!compare_mat(test_mat,mat,3)) {
75  printf("Test Failed!!\n");
76  return;
77  }
78  if(!compare_mat(ident_mat,out_mat,3)) {
79  printf("Identity output Test Failed!!\n");
80  return;
81  }
82 
83 
84  //Test for 4x4 matrix
85  memset(ident_mat,0,sizeof(ident_mat));
86  for(uint8_t i=0; i<4; i++) {
87  ident_mat[i*4+i] = 1.0f;
88  }
89  if(inverse(test_mat,mat,4)){
90  out_mat = mat_mul(test_mat,mat,4);
91  inverse(mat,mat,4);
92  } else {
93  hal.console->printf("4x4 Matrix is Singular!\n");
94  return;
95  }
96  printf("\n\n4x4 Test Matrix:\n");
97  show_matrix(test_mat,4);
98  printf("\nInverse of Inverse of matrix\n");
99  show_matrix(mat,4);
100  printf("\nInv(A) * A\n");
101  show_matrix(out_mat,4);
102  printf("\n");
103  if(!compare_mat(test_mat,mat,4)) {
104  printf("Test Failed!!\n");
105  return;
106  }
107  if(!compare_mat(ident_mat,out_mat,4)) {
108  printf("Identity output Test Failed!!\n");
109  return;
110  }
111 
112 
113 
114  //Test for 5x5 matrix
115  memset(ident_mat,0,sizeof(ident_mat));
116  for(uint8_t i=0; i<5; i++) {
117  ident_mat[i*5+i] = 1.0f;
118  }
119  if(inverse(test_mat,mat,5)) {
120  out_mat = mat_mul(test_mat,mat,5);
121  inverse(mat,mat,5);
122  } else {
123  hal.console->printf("5x5 Matrix is Singular!\n");
124  return;
125 
126  }
127 
128  printf("\n\n5x5 Test Matrix:\n");
129  show_matrix(test_mat,5);
130  printf("\nInverse of Inverse of matrix\n");
131  show_matrix(mat,5);
132  printf("\nInv(A) * A\n");
133  show_matrix(out_mat,5);
134  printf("\n");
135  if(!compare_mat(test_mat,mat,5)) {
136  printf("Test Failed!!\n");
137  return;
138  }
139  if(!compare_mat(ident_mat,out_mat,5)) {
140  printf("Identity output Test Failed!!\n");
141  return;
142  }
143 
144  hal.console->printf("All tests succeeded!!\n");
145 }
146 
147 
148 void setup(void)
149 {
150  hal.console->printf("Matrix Algebra test\n\n");
152  hal.console->printf("Matrix Algebra tests done\n\n");
153 }
154 
155 void loop(void) {}
156 
157 AP_HAL_MAIN();
int printf(const char *fmt,...)
Definition: stdio.c:113
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 show_matrix(float *A, int n)
Definition: matrix_alg.cpp:22
AP_HAL_MAIN()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: matrix_alg.cpp:8
#define MAT_ALG_ACCURACY
Definition: matrix_alg.cpp:10
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
void setup(void)
Definition: matrix_alg.cpp:148
const HAL & get_HAL()
static uint16_t get_random(void)
Definition: matrix_alg.cpp:12
static bool compare_mat(const float *A, const float *B, const uint8_t n)
Definition: matrix_alg.cpp:30
static void test_matrix_inverse(void)
Definition: matrix_alg.cpp:42
void loop(void)
Definition: matrix_alg.cpp:155