APM:Libraries
AP_NavEKF2_AirDataFusion.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
4 
5 #include "AP_NavEKF2.h"
6 #include "AP_NavEKF2_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 
10 #include <stdio.h>
11 
12 extern const AP_HAL::HAL& hal;
13 
14 /********************************************************
15 * RESET FUNCTIONS *
16 ********************************************************/
17 
18 /********************************************************
19 * FUSE MEASURED_DATA *
20 ********************************************************/
21 
22 /*
23  * Fuse true airspeed measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
24  * The script file used to generate these and other equations in this filter can be found here:
25  * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
26 */
28 {
29  // start performance timer
31 
32  // declarations
33  float vn;
34  float ve;
35  float vd;
36  float vwn;
37  float vwe;
38  float EAS2TAS = _ahrs->get_EAS2TAS();
39  const float R_TAS = sq(constrain_float(frontend->_easNoise, 0.5f, 5.0f) * constrain_float(EAS2TAS, 0.9f, 10.0f));
40  Vector3 SH_TAS;
41  float SK_TAS;
42  Vector24 H_TAS;
43  float VtasPred;
44 
45  // health is set bad until test passed
46  tasHealth = false;
47 
48  // copy required states to local variable names
49  vn = stateStruct.velocity.x;
50  ve = stateStruct.velocity.y;
51  vd = stateStruct.velocity.z;
52  vwn = stateStruct.wind_vel.x;
53  vwe = stateStruct.wind_vel.y;
54 
55  // calculate the predicted airspeed
56  VtasPred = norm((ve - vwe) , (vn - vwn) , vd);
57  // perform fusion of True Airspeed measurement
58  if (VtasPred > 1.0f)
59  {
60  // calculate observation jacobians
61  SH_TAS[0] = 1.0f/(sqrtf(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
62  SH_TAS[1] = (SH_TAS[0]*(2*ve - 2*vwe))/2;
63  SH_TAS[2] = (SH_TAS[0]*(2*vn - 2*vwn))/2;
64  for (uint8_t i=0; i<=2; i++) H_TAS[i] = 0.0f;
65  H_TAS[3] = SH_TAS[2];
66  H_TAS[4] = SH_TAS[1];
67  H_TAS[5] = vd*SH_TAS[0];
68  H_TAS[22] = -SH_TAS[2];
69  H_TAS[23] = -SH_TAS[1];
70  for (uint8_t i=6; i<=21; i++) H_TAS[i] = 0.0f;
71  // calculate Kalman gains
72  float temp = (R_TAS + SH_TAS[2]*(P[3][3]*SH_TAS[2] + P[4][3]*SH_TAS[1] - P[22][3]*SH_TAS[2] - P[23][3]*SH_TAS[1] + P[5][3]*vd*SH_TAS[0]) + SH_TAS[1]*(P[3][4]*SH_TAS[2] + P[4][4]*SH_TAS[1] - P[22][4]*SH_TAS[2] - P[23][4]*SH_TAS[1] + P[5][4]*vd*SH_TAS[0]) - SH_TAS[2]*(P[3][22]*SH_TAS[2] + P[4][22]*SH_TAS[1] - P[22][22]*SH_TAS[2] - P[23][22]*SH_TAS[1] + P[5][22]*vd*SH_TAS[0]) - SH_TAS[1]*(P[3][23]*SH_TAS[2] + P[4][23]*SH_TAS[1] - P[22][23]*SH_TAS[2] - P[23][23]*SH_TAS[1] + P[5][23]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[3][5]*SH_TAS[2] + P[4][5]*SH_TAS[1] - P[22][5]*SH_TAS[2] - P[23][5]*SH_TAS[1] + P[5][5]*vd*SH_TAS[0]));
73  if (temp >= R_TAS) {
74  SK_TAS = 1.0f / temp;
75  faultStatus.bad_airspeed = false;
76  } else {
77  // the calculation is badly conditioned, so we cannot perform fusion on this step
78  // we reset the covariance matrix and try again next measurement
80  faultStatus.bad_airspeed = true;
81  return;
82  }
83  Kfusion[0] = SK_TAS*(P[0][3]*SH_TAS[2] - P[0][22]*SH_TAS[2] + P[0][4]*SH_TAS[1] - P[0][23]*SH_TAS[1] + P[0][5]*vd*SH_TAS[0]);
84  Kfusion[1] = SK_TAS*(P[1][3]*SH_TAS[2] - P[1][22]*SH_TAS[2] + P[1][4]*SH_TAS[1] - P[1][23]*SH_TAS[1] + P[1][5]*vd*SH_TAS[0]);
85  Kfusion[2] = SK_TAS*(P[2][3]*SH_TAS[2] - P[2][22]*SH_TAS[2] + P[2][4]*SH_TAS[1] - P[2][23]*SH_TAS[1] + P[2][5]*vd*SH_TAS[0]);
86  Kfusion[3] = SK_TAS*(P[3][3]*SH_TAS[2] - P[3][22]*SH_TAS[2] + P[3][4]*SH_TAS[1] - P[3][23]*SH_TAS[1] + P[3][5]*vd*SH_TAS[0]);
87  Kfusion[4] = SK_TAS*(P[4][3]*SH_TAS[2] - P[4][22]*SH_TAS[2] + P[4][4]*SH_TAS[1] - P[4][23]*SH_TAS[1] + P[4][5]*vd*SH_TAS[0]);
88  Kfusion[5] = SK_TAS*(P[5][3]*SH_TAS[2] - P[5][22]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[5][23]*SH_TAS[1] + P[5][5]*vd*SH_TAS[0]);
89  Kfusion[6] = SK_TAS*(P[6][3]*SH_TAS[2] - P[6][22]*SH_TAS[2] + P[6][4]*SH_TAS[1] - P[6][23]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]);
90  Kfusion[7] = SK_TAS*(P[7][3]*SH_TAS[2] - P[7][22]*SH_TAS[2] + P[7][4]*SH_TAS[1] - P[7][23]*SH_TAS[1] + P[7][5]*vd*SH_TAS[0]);
91  Kfusion[8] = SK_TAS*(P[8][3]*SH_TAS[2] - P[8][22]*SH_TAS[2] + P[8][4]*SH_TAS[1] - P[8][23]*SH_TAS[1] + P[8][5]*vd*SH_TAS[0]);
92  Kfusion[9] = SK_TAS*(P[9][3]*SH_TAS[2] - P[9][22]*SH_TAS[2] + P[9][4]*SH_TAS[1] - P[9][23]*SH_TAS[1] + P[9][5]*vd*SH_TAS[0]);
93  Kfusion[10] = SK_TAS*(P[10][3]*SH_TAS[2] - P[10][22]*SH_TAS[2] + P[10][4]*SH_TAS[1] - P[10][23]*SH_TAS[1] + P[10][5]*vd*SH_TAS[0]);
94  Kfusion[11] = SK_TAS*(P[11][3]*SH_TAS[2] - P[11][22]*SH_TAS[2] + P[11][4]*SH_TAS[1] - P[11][23]*SH_TAS[1] + P[11][5]*vd*SH_TAS[0]);
95  Kfusion[12] = SK_TAS*(P[12][3]*SH_TAS[2] - P[12][22]*SH_TAS[2] + P[12][4]*SH_TAS[1] - P[12][23]*SH_TAS[1] + P[12][5]*vd*SH_TAS[0]);
96  Kfusion[13] = SK_TAS*(P[13][3]*SH_TAS[2] - P[13][22]*SH_TAS[2] + P[13][4]*SH_TAS[1] - P[13][23]*SH_TAS[1] + P[13][5]*vd*SH_TAS[0]);
97  Kfusion[14] = SK_TAS*(P[14][3]*SH_TAS[2] - P[14][22]*SH_TAS[2] + P[14][4]*SH_TAS[1] - P[14][23]*SH_TAS[1] + P[14][5]*vd*SH_TAS[0]);
98  Kfusion[15] = SK_TAS*(P[15][3]*SH_TAS[2] - P[15][22]*SH_TAS[2] + P[15][4]*SH_TAS[1] - P[15][23]*SH_TAS[1] + P[15][5]*vd*SH_TAS[0]);
99  Kfusion[22] = SK_TAS*(P[22][3]*SH_TAS[2] - P[22][22]*SH_TAS[2] + P[22][4]*SH_TAS[1] - P[22][23]*SH_TAS[1] + P[22][5]*vd*SH_TAS[0]);
100  Kfusion[23] = SK_TAS*(P[23][3]*SH_TAS[2] - P[23][22]*SH_TAS[2] + P[23][4]*SH_TAS[1] - P[23][23]*SH_TAS[1] + P[23][5]*vd*SH_TAS[0]);
101  // zero Kalman gains to inhibit magnetic field state estimation
102  if (!inhibitMagStates) {
103  Kfusion[16] = SK_TAS*(P[16][3]*SH_TAS[2] - P[16][22]*SH_TAS[2] + P[16][4]*SH_TAS[1] - P[16][23]*SH_TAS[1] + P[16][5]*vd*SH_TAS[0]);
104  Kfusion[17] = SK_TAS*(P[17][3]*SH_TAS[2] - P[17][22]*SH_TAS[2] + P[17][4]*SH_TAS[1] - P[17][23]*SH_TAS[1] + P[17][5]*vd*SH_TAS[0]);
105  Kfusion[18] = SK_TAS*(P[18][3]*SH_TAS[2] - P[18][22]*SH_TAS[2] + P[18][4]*SH_TAS[1] - P[18][23]*SH_TAS[1] + P[18][5]*vd*SH_TAS[0]);
106  Kfusion[19] = SK_TAS*(P[19][3]*SH_TAS[2] - P[19][22]*SH_TAS[2] + P[19][4]*SH_TAS[1] - P[19][23]*SH_TAS[1] + P[19][5]*vd*SH_TAS[0]);
107  Kfusion[20] = SK_TAS*(P[20][3]*SH_TAS[2] - P[20][22]*SH_TAS[2] + P[20][4]*SH_TAS[1] - P[20][23]*SH_TAS[1] + P[20][5]*vd*SH_TAS[0]);
108  Kfusion[21] = SK_TAS*(P[21][3]*SH_TAS[2] - P[21][22]*SH_TAS[2] + P[21][4]*SH_TAS[1] - P[21][23]*SH_TAS[1] + P[21][5]*vd*SH_TAS[0]);
109  } else {
110  for (uint8_t i=16; i<=21; i++) {
111  Kfusion[i] = 0.0f;
112  }
113  }
114 
115  // calculate measurement innovation variance
116  varInnovVtas = 1.0f/SK_TAS;
117 
118  // calculate measurement innovation
119  innovVtas = VtasPred - tasDataDelayed.tas;
120 
121  // calculate the innovation consistency test ratio
122  tasTestRatio = sq(innovVtas) / (sq(MAX(0.01f * (float)frontend->_tasInnovGate, 1.0f)) * varInnovVtas);
123 
124  // fail if the ratio is > 1, but don't fail if bad IMU data
125  tasHealth = ((tasTestRatio < 1.0f) || badIMUdata);
127 
128  // test the ratio before fusing data, forcing fusion if airspeed and position are timed out as we have no choice but to try and use airspeed to constrain error growth
129  if (tasHealth || (tasTimeout && posTimeout)) {
130 
131  // restart the counter
133 
134 
135  // zero the attitude error state - by definition it is assumed to be zero before each observaton fusion
137 
138  // correct the state vector
139  for (uint8_t j= 0; j<=stateIndexLim; j++) {
140  statesArray[j] = statesArray[j] - Kfusion[j] * innovVtas;
141  }
142 
143  // the first 3 states represent the angular misalignment vector. This is
144  // is used to correct the estimated quaternion on the current time step
146 
147  // correct the covariance P = (I - K*H)*P
148  // take advantage of the empty columns in KH to reduce the
149  // number of operations
150  for (unsigned i = 0; i<=stateIndexLim; i++) {
151  for (unsigned j = 0; j<=2; j++) {
152  KH[i][j] = 0.0f;
153  }
154  for (unsigned j = 3; j<=5; j++) {
155  KH[i][j] = Kfusion[i] * H_TAS[j];
156  }
157  for (unsigned j = 6; j<=21; j++) {
158  KH[i][j] = 0.0f;
159  }
160  for (unsigned j = 22; j<=23; j++) {
161  KH[i][j] = Kfusion[i] * H_TAS[j];
162  }
163  }
164  for (unsigned j = 0; j<=stateIndexLim; j++) {
165  for (unsigned i = 0; i<=stateIndexLim; i++) {
166  ftype res = 0;
167  res += KH[i][3] * P[3][j];
168  res += KH[i][4] * P[4][j];
169  res += KH[i][5] * P[5][j];
170  res += KH[i][22] * P[22][j];
171  res += KH[i][23] * P[23][j];
172  KHP[i][j] = res;
173  }
174  }
175  for (unsigned i = 0; i<=stateIndexLim; i++) {
176  for (unsigned j = 0; j<=stateIndexLim; j++) {
177  P[i][j] = P[i][j] - KHP[i][j];
178  }
179  }
180  }
181  }
182 
183  // force the covariance matrix to me symmetrical and limit the variances to prevent ill-condiioning.
184  ForceSymmetry();
186 
187  // stop performance timer
189 }
190 
191 // select fusion of true airspeed measurements
193 {
194  // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
195  // If so, don't fuse measurements on this time step to reduce frame over-runs
196  // Only allow one time slip to prevent high rate magnetometer data locking out fusion of other measurements
197  if (magFusePerformed && dtIMUavg < 0.005f && !airSpdFusionDelayed) {
198  airSpdFusionDelayed = true;
199  return;
200  } else {
201  airSpdFusionDelayed = false;
202  }
203 
204  // get true airspeed measurement
205  readAirSpdData();
206 
207  // If we haven't received airspeed data for a while, then declare the airspeed data as being timed out
209  tasTimeout = true;
210  }
211 
212  // if the filter is initialised, wind states are not inhibited and we have data to fuse, then perform TAS fusion
214  FuseAirspeed();
216  }
217 }
218 
219 
220 // select fusion of synthetic sideslip measurements
221 // synthetic sidelip fusion only works for fixed wing aircraft and relies on the average sideslip being close to zero
222 // it requires a stable wind for best results and should not be used for aerobatic flight with manoeuvres that induce large sidslip angles (eg knife-edge, spins, etc)
224 {
225  // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
226  // If so, don't fuse measurements on this time step to reduce frame over-runs
227  // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
228  if (magFusePerformed && dtIMUavg < 0.005f && !sideSlipFusionDelayed) {
229  sideSlipFusionDelayed = true;
230  return;
231  } else {
232  sideSlipFusionDelayed = false;
233  }
234 
235  // set true when the fusion time interval has triggered
236  bool f_timeTrigger = ((imuSampleTime_ms - prevBetaStep_ms) >= frontend->betaAvg_ms);
237  // set true when use of synthetic sideslip fusion is necessary because we have limited sensor data or are dead reckoning position
239  // set true when sideslip fusion is feasible (requires zero sideslip assumption to be valid and use of wind states)
240  bool f_feasible = (assume_zero_sideslip() && !inhibitWindStates);
241  // use synthetic sideslip fusion if feasible, required and enough time has lapsed since the last fusion
242  if (f_feasible && f_required && f_timeTrigger) {
243  FuseSideslip();
245  }
246 }
247 
248 /*
249  * Fuse sythetic sideslip measurement of zero using explicit algebraic equations generated with Matlab symbolic toolbox.
250  * The script file used to generate these and other equations in this filter can be found here:
251  * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
252 */
254 {
255  // start performance timer
257 
258  // declarations
259  float q0;
260  float q1;
261  float q2;
262  float q3;
263  float vn;
264  float ve;
265  float vd;
266  float vwn;
267  float vwe;
268  const float R_BETA = 0.03f; // assume a sideslip angle RMS of ~10 deg
269  Vector10 SH_BETA;
270  Vector5 SK_BETA;
271  Vector3f vel_rel_wind;
272  Vector24 H_BETA;
273  float innovBeta;
274 
275  // copy required states to local variable names
276  q0 = stateStruct.quat[0];
277  q1 = stateStruct.quat[1];
278  q2 = stateStruct.quat[2];
279  q3 = stateStruct.quat[3];
280  vn = stateStruct.velocity.x;
281  ve = stateStruct.velocity.y;
282  vd = stateStruct.velocity.z;
283  vwn = stateStruct.wind_vel.x;
284  vwe = stateStruct.wind_vel.y;
285 
286  // calculate predicted wind relative velocity in NED
287  vel_rel_wind.x = vn - vwn;
288  vel_rel_wind.y = ve - vwe;
289  vel_rel_wind.z = vd;
290 
291  // rotate into body axes
292  vel_rel_wind = prevTnb * vel_rel_wind;
293 
294  // perform fusion of assumed sideslip = 0
295  if (vel_rel_wind.x > 5.0f)
296  {
297  // Calculate observation jacobians
298  SH_BETA[0] = (vn - vwn)*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2);
299  if (fabsf(SH_BETA[0]) <= 1e-9f) {
300  faultStatus.bad_sideslip = true;
301  return;
302  } else {
303  faultStatus.bad_sideslip = false;
304  }
305  SH_BETA[0] = (vn - vwn)*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2);
306  SH_BETA[1] = (ve - vwe)*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + vd*(2*q0*q1 + 2*q2*q3) - (vn - vwn)*(2*q0*q3 - 2*q1*q2);
307  SH_BETA[2] = vd*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) - (ve - vwe)*(2*q0*q1 - 2*q2*q3) + (vn - vwn)*(2*q0*q2 + 2*q1*q3);
308  SH_BETA[3] = 1/sq(SH_BETA[0]);
309  SH_BETA[4] = (sq(q0) - sq(q1) + sq(q2) - sq(q3))/SH_BETA[0];
310  SH_BETA[5] = sq(q0) + sq(q1) - sq(q2) - sq(q3);
311  SH_BETA[6] = 1/SH_BETA[0];
312  SH_BETA[7] = 2*q0*q3;
313  SH_BETA[8] = SH_BETA[7] + 2*q1*q2;
314  SH_BETA[9] = SH_BETA[7] - 2*q1*q2;
315  H_BETA[0] = SH_BETA[2]*SH_BETA[6];
316  H_BETA[1] = SH_BETA[1]*SH_BETA[2]*SH_BETA[3];
317  H_BETA[2] = - sq(SH_BETA[1])*SH_BETA[3] - 1;
318  H_BETA[3] = - SH_BETA[6]*SH_BETA[9] - SH_BETA[1]*SH_BETA[3]*SH_BETA[5];
319  H_BETA[4] = SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8];
320  H_BETA[5] = SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3);
321  for (uint8_t i=6; i<=21; i++) {
322  H_BETA[i] = 0.0f;
323  }
324  H_BETA[22] = SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5];
325  H_BETA[23] = SH_BETA[1]*SH_BETA[3]*SH_BETA[8] - SH_BETA[4];
326 
327  // Calculate Kalman gains
328  float temp = (R_BETA + (SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8])*(P[22][4]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][4]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][4]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][4]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][4]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][4]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][4]*SH_BETA[2]*SH_BETA[6] + P[1][4]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) - (SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8])*(P[22][23]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][23]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][23]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][23]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][23]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][23]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][23]*SH_BETA[2]*SH_BETA[6] + P[1][23]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) - (SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5])*(P[22][3]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][3]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][3]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][3]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][3]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][3]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][3]*SH_BETA[2]*SH_BETA[6] + P[1][3]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + (SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5])*(P[22][22]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][22]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][22]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][22]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][22]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][22]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][22]*SH_BETA[2]*SH_BETA[6] + P[1][22]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) - (sq(SH_BETA[1])*SH_BETA[3] + 1)*(P[22][2]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][2]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][2]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][2]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][2]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][2]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][2]*SH_BETA[2]*SH_BETA[6] + P[1][2]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + (SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3))*(P[22][5]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][5]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][5]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][5]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][5]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][5]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][5]*SH_BETA[2]*SH_BETA[6] + P[1][5]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + SH_BETA[2]*SH_BETA[6]*(P[22][0]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][0]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][0]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][0]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][0]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][0]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][0]*SH_BETA[2]*SH_BETA[6] + P[1][0]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + SH_BETA[1]*SH_BETA[2]*SH_BETA[3]*(P[22][1]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][1]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][1]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][1]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][1]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][1]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][1]*SH_BETA[2]*SH_BETA[6] + P[1][1]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]));
329  if (temp >= R_BETA) {
330  SK_BETA[0] = 1.0f / temp;
331  faultStatus.bad_sideslip = false;
332  } else {
333  // the calculation is badly conditioned, so we cannot perform fusion on this step
334  // we reset the covariance matrix and try again next measurement
335  CovarianceInit();
336  faultStatus.bad_sideslip = true;
337  return;
338  }
339  SK_BETA[1] = SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3);
340  SK_BETA[2] = SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5];
341  SK_BETA[3] = SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8];
342  SK_BETA[4] = sq(SH_BETA[1])*SH_BETA[3] + 1;
343  Kfusion[0] = SK_BETA[0]*(P[0][5]*SK_BETA[1] - P[0][2]*SK_BETA[4] - P[0][3]*SK_BETA[2] + P[0][4]*SK_BETA[3] + P[0][22]*SK_BETA[2] - P[0][23]*SK_BETA[3] + P[0][0]*SH_BETA[6]*SH_BETA[2] + P[0][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
344  Kfusion[1] = SK_BETA[0]*(P[1][5]*SK_BETA[1] - P[1][2]*SK_BETA[4] - P[1][3]*SK_BETA[2] + P[1][4]*SK_BETA[3] + P[1][22]*SK_BETA[2] - P[1][23]*SK_BETA[3] + P[1][0]*SH_BETA[6]*SH_BETA[2] + P[1][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
345  Kfusion[2] = SK_BETA[0]*(P[2][5]*SK_BETA[1] - P[2][2]*SK_BETA[4] - P[2][3]*SK_BETA[2] + P[2][4]*SK_BETA[3] + P[2][22]*SK_BETA[2] - P[2][23]*SK_BETA[3] + P[2][0]*SH_BETA[6]*SH_BETA[2] + P[2][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
346  Kfusion[3] = SK_BETA[0]*(P[3][5]*SK_BETA[1] - P[3][2]*SK_BETA[4] - P[3][3]*SK_BETA[2] + P[3][4]*SK_BETA[3] + P[3][22]*SK_BETA[2] - P[3][23]*SK_BETA[3] + P[3][0]*SH_BETA[6]*SH_BETA[2] + P[3][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
347  Kfusion[4] = SK_BETA[0]*(P[4][5]*SK_BETA[1] - P[4][2]*SK_BETA[4] - P[4][3]*SK_BETA[2] + P[4][4]*SK_BETA[3] + P[4][22]*SK_BETA[2] - P[4][23]*SK_BETA[3] + P[4][0]*SH_BETA[6]*SH_BETA[2] + P[4][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
348  Kfusion[5] = SK_BETA[0]*(P[5][5]*SK_BETA[1] - P[5][2]*SK_BETA[4] - P[5][3]*SK_BETA[2] + P[5][4]*SK_BETA[3] + P[5][22]*SK_BETA[2] - P[5][23]*SK_BETA[3] + P[5][0]*SH_BETA[6]*SH_BETA[2] + P[5][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
349  Kfusion[6] = SK_BETA[0]*(P[6][5]*SK_BETA[1] - P[6][2]*SK_BETA[4] - P[6][3]*SK_BETA[2] + P[6][4]*SK_BETA[3] + P[6][22]*SK_BETA[2] - P[6][23]*SK_BETA[3] + P[6][0]*SH_BETA[6]*SH_BETA[2] + P[6][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
350  Kfusion[7] = SK_BETA[0]*(P[7][5]*SK_BETA[1] - P[7][2]*SK_BETA[4] - P[7][3]*SK_BETA[2] + P[7][4]*SK_BETA[3] + P[7][22]*SK_BETA[2] - P[7][23]*SK_BETA[3] + P[7][0]*SH_BETA[6]*SH_BETA[2] + P[7][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
351  Kfusion[8] = SK_BETA[0]*(P[8][5]*SK_BETA[1] - P[8][2]*SK_BETA[4] - P[8][3]*SK_BETA[2] + P[8][4]*SK_BETA[3] + P[8][22]*SK_BETA[2] - P[8][23]*SK_BETA[3] + P[8][0]*SH_BETA[6]*SH_BETA[2] + P[8][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
352  Kfusion[9] = SK_BETA[0]*(P[9][5]*SK_BETA[1] - P[9][2]*SK_BETA[4] - P[9][3]*SK_BETA[2] + P[9][4]*SK_BETA[3] + P[9][22]*SK_BETA[2] - P[9][23]*SK_BETA[3] + P[9][0]*SH_BETA[6]*SH_BETA[2] + P[9][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
353  Kfusion[10] = SK_BETA[0]*(P[10][5]*SK_BETA[1] - P[10][2]*SK_BETA[4] - P[10][3]*SK_BETA[2] + P[10][4]*SK_BETA[3] + P[10][22]*SK_BETA[2] - P[10][23]*SK_BETA[3] + P[10][0]*SH_BETA[6]*SH_BETA[2] + P[10][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
354  Kfusion[11] = SK_BETA[0]*(P[11][5]*SK_BETA[1] - P[11][2]*SK_BETA[4] - P[11][3]*SK_BETA[2] + P[11][4]*SK_BETA[3] + P[11][22]*SK_BETA[2] - P[11][23]*SK_BETA[3] + P[11][0]*SH_BETA[6]*SH_BETA[2] + P[11][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
355  Kfusion[12] = SK_BETA[0]*(P[12][5]*SK_BETA[1] - P[12][2]*SK_BETA[4] - P[12][3]*SK_BETA[2] + P[12][4]*SK_BETA[3] + P[12][22]*SK_BETA[2] - P[12][23]*SK_BETA[3] + P[12][0]*SH_BETA[6]*SH_BETA[2] + P[12][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
356  Kfusion[13] = SK_BETA[0]*(P[13][5]*SK_BETA[1] - P[13][2]*SK_BETA[4] - P[13][3]*SK_BETA[2] + P[13][4]*SK_BETA[3] + P[13][22]*SK_BETA[2] - P[13][23]*SK_BETA[3] + P[13][0]*SH_BETA[6]*SH_BETA[2] + P[13][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
357  Kfusion[14] = SK_BETA[0]*(P[14][5]*SK_BETA[1] - P[14][2]*SK_BETA[4] - P[14][3]*SK_BETA[2] + P[14][4]*SK_BETA[3] + P[14][22]*SK_BETA[2] - P[14][23]*SK_BETA[3] + P[14][0]*SH_BETA[6]*SH_BETA[2] + P[14][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
358  Kfusion[15] = SK_BETA[0]*(P[15][5]*SK_BETA[1] - P[15][2]*SK_BETA[4] - P[15][3]*SK_BETA[2] + P[15][4]*SK_BETA[3] + P[15][22]*SK_BETA[2] - P[15][23]*SK_BETA[3] + P[15][0]*SH_BETA[6]*SH_BETA[2] + P[15][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
359  Kfusion[22] = SK_BETA[0]*(P[22][5]*SK_BETA[1] - P[22][2]*SK_BETA[4] - P[22][3]*SK_BETA[2] + P[22][4]*SK_BETA[3] + P[22][22]*SK_BETA[2] - P[22][23]*SK_BETA[3] + P[22][0]*SH_BETA[6]*SH_BETA[2] + P[22][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
360  Kfusion[23] = SK_BETA[0]*(P[23][5]*SK_BETA[1] - P[23][2]*SK_BETA[4] - P[23][3]*SK_BETA[2] + P[23][4]*SK_BETA[3] + P[23][22]*SK_BETA[2] - P[23][23]*SK_BETA[3] + P[23][0]*SH_BETA[6]*SH_BETA[2] + P[23][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
361  // zero Kalman gains to inhibit magnetic field state estimation
362  if (!inhibitMagStates) {
363  Kfusion[16] = SK_BETA[0]*(P[16][5]*SK_BETA[1] - P[16][2]*SK_BETA[4] - P[16][3]*SK_BETA[2] + P[16][4]*SK_BETA[3] + P[16][22]*SK_BETA[2] - P[16][23]*SK_BETA[3] + P[16][0]*SH_BETA[6]*SH_BETA[2] + P[16][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
364  Kfusion[17] = SK_BETA[0]*(P[17][5]*SK_BETA[1] - P[17][2]*SK_BETA[4] - P[17][3]*SK_BETA[2] + P[17][4]*SK_BETA[3] + P[17][22]*SK_BETA[2] - P[17][23]*SK_BETA[3] + P[17][0]*SH_BETA[6]*SH_BETA[2] + P[17][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
365  Kfusion[18] = SK_BETA[0]*(P[18][5]*SK_BETA[1] - P[18][2]*SK_BETA[4] - P[18][3]*SK_BETA[2] + P[18][4]*SK_BETA[3] + P[18][22]*SK_BETA[2] - P[18][23]*SK_BETA[3] + P[18][0]*SH_BETA[6]*SH_BETA[2] + P[18][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
366  Kfusion[19] = SK_BETA[0]*(P[19][5]*SK_BETA[1] - P[19][2]*SK_BETA[4] - P[19][3]*SK_BETA[2] + P[19][4]*SK_BETA[3] + P[19][22]*SK_BETA[2] - P[19][23]*SK_BETA[3] + P[19][0]*SH_BETA[6]*SH_BETA[2] + P[19][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
367  Kfusion[20] = SK_BETA[0]*(P[20][5]*SK_BETA[1] - P[20][2]*SK_BETA[4] - P[20][3]*SK_BETA[2] + P[20][4]*SK_BETA[3] + P[20][22]*SK_BETA[2] - P[20][23]*SK_BETA[3] + P[20][0]*SH_BETA[6]*SH_BETA[2] + P[20][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
368  Kfusion[21] = SK_BETA[0]*(P[21][5]*SK_BETA[1] - P[21][2]*SK_BETA[4] - P[21][3]*SK_BETA[2] + P[21][4]*SK_BETA[3] + P[21][22]*SK_BETA[2] - P[21][23]*SK_BETA[3] + P[21][0]*SH_BETA[6]*SH_BETA[2] + P[21][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
369  } else {
370  for (uint8_t i=16; i<=21; i++) {
371  Kfusion[i] = 0.0f;
372  }
373  }
374 
375  // calculate predicted sideslip angle and innovation using small angle approximation
376  innovBeta = vel_rel_wind.y / vel_rel_wind.x;
377 
378  // reject measurement if greater than 3-sigma inconsistency
379  if (innovBeta > 0.5f) {
380  return;
381  }
382 
383  // zero the attitude error state - by definition it is assumed to be zero before each observaton fusion
385 
386  // correct the state vector
387  for (uint8_t j= 0; j<=stateIndexLim; j++) {
388  statesArray[j] = statesArray[j] - Kfusion[j] * innovBeta;
389  }
390 
391  // the first 3 states represent the angular misalignment vector. This is
392  // is used to correct the estimated quaternion on the current time step
394 
395  // correct the covariance P = (I - K*H)*P
396  // take advantage of the empty columns in KH to reduce the
397  // number of operations
398  for (unsigned i = 0; i<=stateIndexLim; i++) {
399  for (unsigned j = 0; j<=5; j++) {
400  KH[i][j] = Kfusion[i] * H_BETA[j];
401  }
402  for (unsigned j = 6; j<=21; j++) {
403  KH[i][j] = 0.0f;
404  }
405  for (unsigned j = 22; j<=23; j++) {
406  KH[i][j] = Kfusion[i] * H_BETA[j];
407  }
408  }
409  for (unsigned j = 0; j<=stateIndexLim; j++) {
410  for (unsigned i = 0; i<=stateIndexLim; i++) {
411  ftype res = 0;
412  res += KH[i][0] * P[0][j];
413  res += KH[i][1] * P[1][j];
414  res += KH[i][2] * P[2][j];
415  res += KH[i][3] * P[3][j];
416  res += KH[i][4] * P[4][j];
417  res += KH[i][5] * P[5][j];
418  res += KH[i][22] * P[22][j];
419  res += KH[i][23] * P[23][j];
420  KHP[i][j] = res;
421  }
422  }
423  for (unsigned i = 0; i<=stateIndexLim; i++) {
424  for (unsigned j = 0; j<=stateIndexLim; j++) {
425  P[i][j] = P[i][j] - KHP[i][j];
426  }
427  }
428  }
429 
430  // force the covariance matrix to be symmetrical and limit the variances to prevent ill-condiioning.
431  ForceSymmetry();
433 
434  // stop the performance timer
436 }
437 
438 /********************************************************
439 * MISC FUNCTIONS *
440 ********************************************************/
441 
442 
443 #endif // HAL_CPU_CLASS
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
uint32_t prevTasStep_ms
AP_HAL::Util::perf_counter_t _perf_FuseSideslip
AP_Float _easNoise
Definition: AP_NavEKF2.h:356
ftype Vector10[10]
NavEKF2 * frontend
bool assume_zero_sideslip(void) const
const uint16_t posRetryTimeNoVel_ms
Definition: AP_NavEKF2.h:408
Vector28 statesArray
const AP_AHRS * _ahrs
AP_HAL::Util * util
Definition: HAL.h:115
struct NavEKF2_core::state_elements & stateStruct
uint32_t imuSampleTime_ms
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
ftype Vector5[5]
T y
Definition: vector2.h:37
AP_HAL::Util::perf_counter_t _perf_FuseAirspeed
struct NavEKF2_core::@145 faultStatus
#define f(i)
const uint16_t tasRetryTime_ms
Definition: AP_NavEKF2.h:411
uint32_t prevBetaStep_ms
T y
Definition: vector3.h:67
bool useAirspeed(void) const
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
T z
Definition: vector3.h:67
const uint8_t betaAvg_ms
Definition: AP_NavEKF2.h:416
ftype Vector24[24]
Matrix3f prevTnb
bool use_compass(void) const
bool sideSlipFusionDelayed
AP_Int16 _tasInnovGate
Definition: AP_NavEKF2.h:372
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
tas_elements tasDataNew
uint8_t stateIndexLim
float sq(const T val)
Definition: AP_Math.h:170
bool airSpdFusionDelayed
void rotate(const Vector3f &v)
Definition: quaternion.cpp:182
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint32_t lastPosPassTime_ms
uint32_t lastTasPassTime_ms
tas_elements tasDataDelayed
void zero()
Definition: vector3.h:182
Vector28 Kfusion
T x
Definition: vector3.h:67