APM:Libraries
AP_NavEKF3_RngBcnFusion.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_NavEKF3.h"
6 #include "AP_NavEKF3_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 #include <GCS_MAVLink/GCS.h>
10 
11 extern const AP_HAL::HAL& hal;
12 
13 /********************************************************
14 * FUSE MEASURED_DATA *
15 ********************************************************/
16 
17 // select fusion of range beacon measurements
19 {
20  // read range data from the sensor and check for new data in the buffer
22 
23  // Determine if we need to fuse range beacon data on this time step
24  if (rngBcnDataToFuse) {
25  if (PV_AidingMode == AID_ABSOLUTE) {
27  if (!bcnOriginEstInit) {
28  bcnOriginEstInit = true;
31  }
32  // If we aren't using GPS, then the beacons are used as the primary means of position reference
33  FuseRngBcn();
34  } else {
35  // If we are using GPS, then GPS is the primary reference, but we continue to use the beacon data
36  // to calculate an independant position that is used to update the beacon position offset if we need to
37  // start using beacon data as the primary reference.
39  // record that the beacon origin needs to be initialised
40  bcnOriginEstInit = false;
41  }
42  } else {
43  // If we aren't able to use the data in the main filter, use a simple 3-state filter to estimate position only
45  // record that the beacon origin needs to be initialised
46  bcnOriginEstInit = false;
47  }
48  }
49 }
50 
52 {
53  // declarations
54  float pn;
55  float pe;
56  float pd;
57  float bcn_pn;
58  float bcn_pe;
59  float bcn_pd;
60  const float R_BCN = sq(MAX(rngBcnDataDelayed.rngErr , 0.1f));
61  float rngPred;
62 
63  // health is set bad until test passed
64  rngBcnHealth = false;
65 
67  // calculate the vertical offset from EKF datum to beacon datum
69  } else {
70  bcnPosOffsetNED.z = 0.0f;
71  }
72 
73  // copy required states to local variable names
74  pn = stateStruct.position.x;
75  pe = stateStruct.position.y;
76  pd = stateStruct.position.z;
80 
81  // predicted range
83  rngPred = deltaPosNED.length();
84 
85  // calculate measurement innovation
86  innovRngBcn = rngPred - rngBcnDataDelayed.rng;
87 
88  // perform fusion of range measurement
89  if (rngPred > 0.1f)
90  {
91  // calculate observation jacobians
92  float H_BCN[24];
93  memset(H_BCN, 0, sizeof(H_BCN));
94  float t2 = bcn_pd-pd;
95  float t3 = bcn_pe-pe;
96  float t4 = bcn_pn-pn;
97  float t5 = t2*t2;
98  float t6 = t3*t3;
99  float t7 = t4*t4;
100  float t8 = t5+t6+t7;
101  float t9 = 1.0f/sqrtf(t8);
102  H_BCN[7] = -t4*t9;
103  H_BCN[8] = -t3*t9;
104  // If we are not using the beacons as a height reference, we pretend that the beacons
105  // are a the same height as the flight vehicle when calculating the observation derivatives
106  // and Kalman gains
107  // TODO - less hacky way of achieving this, preferably using an alternative derivation
109  t2 = 0.0f;
110  }
111  H_BCN[9] = -t2*t9;
112 
113  // calculate Kalman gains
114  float t10 = P[9][9]*t2*t9;
115  float t11 = P[8][9]*t3*t9;
116  float t12 = P[7][9]*t4*t9;
117  float t13 = t10+t11+t12;
118  float t14 = t2*t9*t13;
119  float t15 = P[9][8]*t2*t9;
120  float t16 = P[8][8]*t3*t9;
121  float t17 = P[7][8]*t4*t9;
122  float t18 = t15+t16+t17;
123  float t19 = t3*t9*t18;
124  float t20 = P[9][7]*t2*t9;
125  float t21 = P[8][7]*t3*t9;
126  float t22 = P[7][7]*t4*t9;
127  float t23 = t20+t21+t22;
128  float t24 = t4*t9*t23;
129  varInnovRngBcn = R_BCN+t14+t19+t24;
130  float t26;
131  if (varInnovRngBcn >= R_BCN) {
132  t26 = 1.0f/varInnovRngBcn;
133  faultStatus.bad_rngbcn = false;
134  } else {
135  // the calculation is badly conditioned, so we cannot perform fusion on this step
136  // we reset the covariance matrix and try again next measurement
137  CovarianceInit();
138  faultStatus.bad_rngbcn = true;
139  return;
140  }
141 
142  Kfusion[0] = -t26*(P[0][7]*t4*t9+P[0][8]*t3*t9+P[0][9]*t2*t9);
143  Kfusion[1] = -t26*(P[1][7]*t4*t9+P[1][8]*t3*t9+P[1][9]*t2*t9);
144  Kfusion[2] = -t26*(P[2][7]*t4*t9+P[2][8]*t3*t9+P[2][9]*t2*t9);
145  Kfusion[3] = -t26*(P[3][7]*t4*t9+P[3][8]*t3*t9+P[3][9]*t2*t9);
146  Kfusion[4] = -t26*(P[4][7]*t4*t9+P[4][8]*t3*t9+P[4][9]*t2*t9);
147  Kfusion[5] = -t26*(P[5][7]*t4*t9+P[5][8]*t3*t9+P[5][9]*t2*t9);
148  Kfusion[7] = -t26*(t22+P[7][8]*t3*t9+P[7][9]*t2*t9);
149  Kfusion[8] = -t26*(t16+P[8][7]*t4*t9+P[8][9]*t2*t9);
150 
152  Kfusion[10] = -t26*(P[10][7]*t4*t9+P[10][8]*t3*t9+P[10][9]*t2*t9);
153  Kfusion[11] = -t26*(P[11][7]*t4*t9+P[11][8]*t3*t9+P[11][9]*t2*t9);
154  Kfusion[12] = -t26*(P[12][7]*t4*t9+P[12][8]*t3*t9+P[12][9]*t2*t9);
155  } else {
156  // zero indexes 10 to 12 = 3*4 bytes
157  memset(&Kfusion[10], 0, 12);
158  }
159 
161  Kfusion[13] = -t26*(P[13][7]*t4*t9+P[13][8]*t3*t9+P[13][9]*t2*t9);
162  Kfusion[14] = -t26*(P[14][7]*t4*t9+P[14][8]*t3*t9+P[14][9]*t2*t9);
163  Kfusion[15] = -t26*(P[15][7]*t4*t9+P[15][8]*t3*t9+P[15][9]*t2*t9);
164  } else {
165  // zero indexes 13 to 15 = 3*4 bytes
166  memset(&Kfusion[13], 0, 12);
167  }
168 
169  // only allow the range observations to modify the vertical states if we are using it as a height reference
171  Kfusion[6] = -t26*(P[6][7]*t4*t9+P[6][8]*t3*t9+P[6][9]*t2*t9);
172  Kfusion[9] = -t26*(t10+P[9][7]*t4*t9+P[9][8]*t3*t9);
173  } else {
174  Kfusion[6] = 0.0f;
175  Kfusion[9] = 0.0f;
176  }
177 
178  if (!inhibitMagStates) {
179  Kfusion[16] = -t26*(P[16][7]*t4*t9+P[16][8]*t3*t9+P[16][9]*t2*t9);
180  Kfusion[17] = -t26*(P[17][7]*t4*t9+P[17][8]*t3*t9+P[17][9]*t2*t9);
181  Kfusion[18] = -t26*(P[18][7]*t4*t9+P[18][8]*t3*t9+P[18][9]*t2*t9);
182  Kfusion[19] = -t26*(P[19][7]*t4*t9+P[19][8]*t3*t9+P[19][9]*t2*t9);
183  Kfusion[20] = -t26*(P[20][7]*t4*t9+P[20][8]*t3*t9+P[20][9]*t2*t9);
184  Kfusion[21] = -t26*(P[21][7]*t4*t9+P[21][8]*t3*t9+P[21][9]*t2*t9);
185  } else {
186  // zero indexes 16 to 21 = 6*4 bytes
187  memset(&Kfusion[16], 0, 24);
188  }
189 
190  if (!inhibitWindStates) {
191  Kfusion[22] = -t26*(P[22][7]*t4*t9+P[22][8]*t3*t9+P[22][9]*t2*t9);
192  Kfusion[23] = -t26*(P[23][7]*t4*t9+P[23][8]*t3*t9+P[23][9]*t2*t9);
193  } else {
194  // zero indexes 22 to 23 = 2*4 bytes
195  memset(&Kfusion[22], 0, 8);
196  }
197 
198  // Calculate innovation using the selected offset value
201 
202  // calculate the innovation consistency test ratio
204 
205  // fail if the ratio is > 1, but don't fail if bad IMU data
206  rngBcnHealth = ((rngBcnTestRatio < 1.0f) || badIMUdata);
207 
208  // test the ratio before fusing data
209  if (rngBcnHealth) {
210 
211  // restart the counter
213 
214  // correct the covariance P = (I - K*H)*P
215  // take advantage of the empty columns in KH to reduce the
216  // number of operations
217  for (unsigned i = 0; i<=stateIndexLim; i++) {
218  for (unsigned j = 0; j<=6; j++) {
219  KH[i][j] = 0.0f;
220  }
221  for (unsigned j = 7; j<=9; j++) {
222  KH[i][j] = Kfusion[i] * H_BCN[j];
223  }
224  for (unsigned j = 10; j<=23; j++) {
225  KH[i][j] = 0.0f;
226  }
227  }
228  for (unsigned j = 0; j<=stateIndexLim; j++) {
229  for (unsigned i = 0; i<=stateIndexLim; i++) {
230  ftype res = 0;
231  res += KH[i][7] * P[7][j];
232  res += KH[i][8] * P[8][j];
233  res += KH[i][9] * P[9][j];
234  KHP[i][j] = res;
235  }
236  }
237  // Check that we are not going to drive any variances negative and skip the update if so
238  bool healthyFusion = true;
239  for (uint8_t i= 0; i<=stateIndexLim; i++) {
240  if (KHP[i][i] > P[i][i]) {
241  healthyFusion = false;
242  }
243  }
244  if (healthyFusion) {
245  // update the covariance matrix
246  for (uint8_t i= 0; i<=stateIndexLim; i++) {
247  for (uint8_t j= 0; j<=stateIndexLim; j++) {
248  P[i][j] = P[i][j] - KHP[i][j];
249  }
250  }
251 
252  // force the covariance matrix to be symmetrical and limit the variances to prevent ill-condiioning.
253  ForceSymmetry();
255 
256  // correct the state vector
257  for (uint8_t j= 0; j<=stateIndexLim; j++) {
258  statesArray[j] = statesArray[j] - Kfusion[j] * innovRngBcn;
259  }
260 
261  // record healthy fusion
262  faultStatus.bad_rngbcn = false;
263 
264  } else {
265  // record bad fusion
266  faultStatus.bad_rngbcn = true;
267 
268  }
269  }
270 
271  // Update the fusion report
277  }
278 }
279 
280 /*
281 Use range beacon measurements to calculate a static position using a 3-state EKF algorithm.
282 Algorithm based on the following:
283 https://github.com/priseborough/InertialNav/blob/master/derivations/range_beacon.m
284 */
286 {
287  // get the estimated range measurement variance
288  const float R_RNG = sq(MAX(rngBcnDataDelayed.rngErr , 0.1f));
289 
290  /*
291  The first thing to do is to check if we have started the alignment and if not, initialise the
292  states and covariance to a first guess. To do this iterate through the available beacons and then
293  initialise the initial position to the mean beacon position. The initial position uncertainty
294  is set to the mean range measurement.
295  */
296  if (!rngBcnAlignmentStarted) {
301  numBcnMeas++;
302 
303  // capture the beacon vertical spread
308  }
309  }
310  if (numBcnMeas >= 100) {
311  rngBcnAlignmentStarted = true;
312  float tempVar = 1.0f / (float)numBcnMeas;
313  // initialise the receiver position to the centre of the beacons and at zero height
314  receiverPos.x = rngBcnPosSum.x * tempVar;
315  receiverPos.y = rngBcnPosSum.y * tempVar;
316  receiverPos.z = 0.0f;
317  receiverPosCov[2][2] = receiverPosCov[1][1] = receiverPosCov[0][0] = rngSum * tempVar;
318  lastBeaconIndex = 0;
319  numBcnMeas = 0;
320  rngBcnPosSum.zero();
321  rngSum = 0.0f;
322  }
323  }
324 
326  numBcnMeas++;
327 
328  if (numBcnMeas >= 100) {
329  // 100 observations is enough for a stable estimate under most conditions
330  // TODO monitor stability of the position estimate
332 
333  }
334 
337  // We are using a different height reference for the main EKF so need to estimate a vertical
338  // position offset to be applied to the beacon system that minimises the range innovations
339  // The position estimate should be stable after 100 iterations so we use a simple dual
340  // hypothesis 1-state EKF to estiate the offset
341  Vector3f refPosNED;
342  refPosNED.x = receiverPos.x;
343  refPosNED.y = receiverPos.y;
344  refPosNED.z = stateStruct.position.z;
345  CalcRangeBeaconPosDownOffset(R_RNG, refPosNED, true);
346 
347  } else {
348  // we are using the beacons as the primary height source, so don't modify their vertical position
349  bcnPosOffsetNED.z = 0.0f;
350 
351  }
352  } else {
354  // The position estimate is not yet stable so we cannot run the 1-state EKF to estimate
355  // beacon system vertical position offset. Instead we initialise the dual hypothesis offset states
356  // using the beacon vertical position, vertical position estimate relative to the beacon origin
357  // and the main EKF vertical position
358 
359  // Calculate the mid vertical position of all beacons
360  float bcnMidPosD = 0.5f * (minBcnPosD + maxBcnPosD);
361 
362  // calculate the delta to the estimated receiver position
363  float delta = receiverPos.z - bcnMidPosD;
364 
365  // calcuate the two hypothesis for our vertical position
366  float receverPosDownMax;
367  float receverPosDownMin;
368  if (delta >= 0.0f) {
369  receverPosDownMax = receiverPos.z;
370  receverPosDownMin = receiverPos.z - 2.0f * delta;
371  } else {
372  receverPosDownMax = receiverPos.z - 2.0f * delta;
373  receverPosDownMin = receiverPos.z;
374  }
375 
376  bcnPosDownOffsetMax = stateStruct.position.z - receverPosDownMin;
377  bcnPosDownOffsetMin = stateStruct.position.z - receverPosDownMax;
378  } else {
379  // We are using the beacons as the primary height reference, so don't modify their vertical position
380  bcnPosOffsetNED.z = 0.0f;
381  }
382  }
383 
384  // Add some process noise to the states at each time step
385  for (uint8_t i= 0; i<=2; i++) {
386  receiverPosCov[i][i] += 0.1f;
387  }
388 
389  // calculate the observation jacobian
393  float t5 = t2*t2;
394  float t6 = t3*t3;
395  float t7 = t4*t4;
396  float t8 = t5+t6+t7;
397  if (t8 < 0.1f) {
398  // calculation will be badly conditioned
399  return;
400  }
401  float t9 = 1.0f/sqrtf(t8);
402  float t10 = rngBcnDataDelayed.beacon_posNED.x*2.0f;
403  float t15 = receiverPos.x*2.0f;
404  float t11 = t10-t15;
405  float t12 = rngBcnDataDelayed.beacon_posNED.y*2.0f;
406  float t14 = receiverPos.y*2.0f;
407  float t13 = t12-t14;
408  float t16 = rngBcnDataDelayed.beacon_posNED.z*2.0f;
409  float t18 = receiverPos.z*2.0f;
410  float t17 = t16-t18;
411  float H_RNG[3];
412  H_RNG[0] = -t9*t11*0.5f;
413  H_RNG[1] = -t9*t13*0.5f;
414  H_RNG[2] = -t9*t17*0.5f;
415 
416  // calculate the Kalman gains
417  float t19 = receiverPosCov[0][0]*t9*t11*0.5f;
418  float t20 = receiverPosCov[1][1]*t9*t13*0.5f;
419  float t21 = receiverPosCov[0][1]*t9*t11*0.5f;
420  float t22 = receiverPosCov[2][1]*t9*t17*0.5f;
421  float t23 = t20+t21+t22;
422  float t24 = t9*t13*t23*0.5f;
423  float t25 = receiverPosCov[1][2]*t9*t13*0.5f;
424  float t26 = receiverPosCov[0][2]*t9*t11*0.5f;
425  float t27 = receiverPosCov[2][2]*t9*t17*0.5f;
426  float t28 = t25+t26+t27;
427  float t29 = t9*t17*t28*0.5f;
428  float t30 = receiverPosCov[1][0]*t9*t13*0.5f;
429  float t31 = receiverPosCov[2][0]*t9*t17*0.5f;
430  float t32 = t19+t30+t31;
431  float t33 = t9*t11*t32*0.5f;
432  varInnovRngBcn = R_RNG+t24+t29+t33;
433  float t35 = 1.0f/varInnovRngBcn;
434  float K_RNG[3];
435  K_RNG[0] = -t35*(t19+receiverPosCov[0][1]*t9*t13*0.5f+receiverPosCov[0][2]*t9*t17*0.5f);
436  K_RNG[1] = -t35*(t20+receiverPosCov[1][0]*t9*t11*0.5f+receiverPosCov[1][2]*t9*t17*0.5f);
437  K_RNG[2] = -t35*(t27+receiverPosCov[2][0]*t9*t11*0.5f+receiverPosCov[2][1]*t9*t13*0.5f);
438 
439  // calculate range measurement innovation
441  deltaPosNED.z -= bcnPosOffsetNED.z;
442  innovRngBcn = deltaPosNED.length() - rngBcnDataDelayed.rng;
443 
444  // calculate the innovation consistency test ratio
446 
447  // fail if the ratio is > 1, but don't fail if bad IMU data
449 
450  // test the ratio before fusing data
451  if (rngBcnHealth) {
452 
453  // update the state
454  receiverPos.x -= K_RNG[0] * innovRngBcn;
455  receiverPos.y -= K_RNG[1] * innovRngBcn;
456  receiverPos.z -= K_RNG[2] * innovRngBcn;
457 
458  // calculate the covariance correction
459  for (unsigned i = 0; i<=2; i++) {
460  for (unsigned j = 0; j<=2; j++) {
461  KH[i][j] = K_RNG[i] * H_RNG[j];
462  }
463  }
464  for (unsigned j = 0; j<=2; j++) {
465  for (unsigned i = 0; i<=2; i++) {
466  ftype res = 0;
467  res += KH[i][0] * receiverPosCov[0][j];
468  res += KH[i][1] * receiverPosCov[1][j];
469  res += KH[i][2] * receiverPosCov[2][j];
470  KHP[i][j] = res;
471  }
472  }
473 
474  // prevent negative variances
475  for (uint8_t i= 0; i<=2; i++) {
476  if (receiverPosCov[i][i] < 0.0f) {
477  receiverPosCov[i][i] = 0.0f;
478  KHP[i][i] = 0.0f;
479  } else if (KHP[i][i] > receiverPosCov[i][i]) {
480  KHP[i][i] = receiverPosCov[i][i];
481  }
482  }
483 
484  // apply the covariance correction
485  for (uint8_t i= 0; i<=2; i++) {
486  for (uint8_t j= 0; j<=2; j++) {
487  receiverPosCov[i][j] -= KHP[i][j];
488  }
489  }
490 
491  // ensure the covariance matrix is symmetric
492  for (uint8_t i=1; i<=2; i++) {
493  for (uint8_t j=0; j<=i-1; j++) {
494  float temp = 0.5f*(receiverPosCov[i][j] + receiverPosCov[j][i]);
495  receiverPosCov[i][j] = temp;
496  receiverPosCov[j][i] = temp;
497  }
498  }
499 
500  }
501 
502  if (numBcnMeas >= 100) {
503  // 100 observations is enough for a stable estimate under most conditions
504  // TODO monitor stability of the position estimate
506  }
507  // Update the fusion report
513  }
514 }
515 
516 /*
517 Run a single state Kalman filter to estimate the vertical position offset of the range beacon constellation
518 Calculate using a high and low hypothesis and select the hypothesis with the lowest innovation sequence
519 */
520 void NavEKF3_core::CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning)
521 {
522  // Handle height offsets between the primary height source and the range beacons by estimating
523  // the beacon systems global vertical position offset using a single state Kalman filter
524  // The estimated offset is used to correct the beacon height when calculating innovations
525  // A high and low estimate is calculated to handle the ambiguity in height associated with beacon positions that are co-planar
526  // The main filter then uses the offset with the smaller innovations
527 
528  float innov; // range measurement innovation (m)
529  float innovVar; // range measurement innovation variance (m^2)
530  float gain; // Kalman gain
531  float obsDeriv; // derivative of observation relative to state
532 
533  const float stateNoiseVar = 0.1f; // State process noise variance
534  const float filtAlpha = 0.1f; // LPF constant
535  const float innovGateWidth = 5.0f; // width of innovation consistency check gate in std
536 
537  // estimate upper value for offset
538 
539  // calculate observation derivative
540  float t2 = rngBcnDataDelayed.beacon_posNED.z - vehiclePosNED.z + bcnPosDownOffsetMax;
541  float t3 = rngBcnDataDelayed.beacon_posNED.y - vehiclePosNED.y;
542  float t4 = rngBcnDataDelayed.beacon_posNED.x - vehiclePosNED.x;
543  float t5 = t2*t2;
544  float t6 = t3*t3;
545  float t7 = t4*t4;
546  float t8 = t5+t6+t7;
547  float t9;
548  if (t8 > 0.1f) {
549  t9 = 1.0f/sqrtf(t8);
550  obsDeriv = t2*t9;
551 
552  // Calculate innovation
553  innov = sqrtf(t8) - rngBcnDataDelayed.rng;
554 
555  // covariance prediction
556  bcnPosOffsetMaxVar += stateNoiseVar;
557 
558  // calculate the innovation variance
559  innovVar = obsDeriv * bcnPosOffsetMaxVar * obsDeriv + obsVar;
560  innovVar = MAX(innovVar, obsVar);
561 
562  // calculate the Kalman gain
563  gain = (bcnPosOffsetMaxVar * obsDeriv) / innovVar;
564 
565  // calculate a filtered state change magnitude to be used to select between the high or low offset
566  float stateChange = innov * gain;
567  maxOffsetStateChangeFilt = (1.0f - filtAlpha) * maxOffsetStateChangeFilt + fminf(fabsf(filtAlpha * stateChange) , 1.0f);
568 
569  // Reject range innovation spikes using a 5-sigma threshold unless aligning
570  if ((sq(innov) < sq(innovGateWidth) * innovVar) || aligning) {
571 
572  // state update
573  bcnPosDownOffsetMax -= stateChange;
574 
575  // covariance update
576  bcnPosOffsetMaxVar -= gain * obsDeriv * bcnPosOffsetMaxVar;
577  bcnPosOffsetMaxVar = MAX(bcnPosOffsetMaxVar, 0.0f);
578  }
579  }
580 
581  // estimate lower value for offset
582 
583  // calculate observation derivative
584  t2 = rngBcnDataDelayed.beacon_posNED.z - vehiclePosNED.z + bcnPosDownOffsetMin;
585  t5 = t2*t2;
586  t8 = t5+t6+t7;
587  if (t8 > 0.1f) {
588  t9 = 1.0f/sqrtf(t8);
589  obsDeriv = t2*t9;
590 
591  // Calculate innovation
592  innov = sqrtf(t8) - rngBcnDataDelayed.rng;
593 
594  // covariance prediction
595  bcnPosOffsetMinVar += stateNoiseVar;
596 
597  // calculate the innovation variance
598  innovVar = obsDeriv * bcnPosOffsetMinVar * obsDeriv + obsVar;
599  innovVar = MAX(innovVar, obsVar);
600 
601  // calculate the Kalman gain
602  gain = (bcnPosOffsetMinVar * obsDeriv) / innovVar;
603 
604  // calculate a filtered state change magnitude to be used to select between the high or low offset
605  float stateChange = innov * gain;
606  minOffsetStateChangeFilt = (1.0f - filtAlpha) * minOffsetStateChangeFilt + fminf(fabsf(filtAlpha * stateChange) , 1.0f);
607 
608  // Reject range innovation spikes using a 5-sigma threshold unless aligning
609  if ((sq(innov) < sq(innovGateWidth) * innovVar) || aligning) {
610 
611  // state update
612  bcnPosDownOffsetMin -= stateChange;
613 
614  // covariance update
615  bcnPosOffsetMinVar -= gain * obsDeriv * bcnPosOffsetMinVar;
616  bcnPosOffsetMinVar = MAX(bcnPosOffsetMinVar, 0.0f);
617  }
618  }
619 
620  // calculate the mid vertical position of all beacons
621  float bcnMidPosD = 0.5f * (minBcnPosD + maxBcnPosD);
622 
623  // ensure the two beacon vertical offset hypothesis place the mid point of the beacons below and above the flight vehicle
624  bcnPosDownOffsetMax = MAX(bcnPosDownOffsetMax, vehiclePosNED.z - bcnMidPosD + 0.5f);
625  bcnPosDownOffsetMin = MIN(bcnPosDownOffsetMin, vehiclePosNED.z - bcnMidPosD - 0.5f);
626 
627  // calculate the innovation for the main filter using the offset that is most stable
628  // apply hysteresis to prevent rapid switching
630  usingMinHypothesis = true;
631  } else if (usingMinHypothesis && (maxOffsetStateChangeFilt < (0.8f * minOffsetStateChangeFilt))) {
632  usingMinHypothesis = false;
633  }
634  if (usingMinHypothesis) {
636  } else {
638  }
639 
640  // apply the vertical offset to the beacon positions
642 }
643 
644 #endif // HAL_CPU_CLASS
t2
Definition: calcH_MAG.c:1
Vector24 statesArray
uint8_t activeHgtSource
t33
Definition: calcH_MAG.c:34
void CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning)
t26
Definition: calcH_MAG.c:27
float maxOffsetStateChangeFilt
Interface definition for the various Ground Control System.
uint8_t lastBeaconIndex
Vector28 Kfusion
t16
Definition: calcH_MAG.c:15
AP_Int16 _rngBcnInnovGate
Definition: AP_NavEKF3.h:410
t24
Definition: calcH_MAG.c:24
t28
Definition: calcH_MAG.c:29
bool rngBcnAlignmentStarted
t35
Definition: calcH_MAG.c:35
t31
Definition: calcH_MAG.c:26
AidingMode PV_AidingMode
struct NavEKF3_core::@153 faultStatus
uint32_t lastRngBcnPassTime_ms
t21
Definition: calcH_MAG.c:20
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
struct NavEKF3_core::state_elements & stateStruct
bool inhibitDelAngBiasStates
t13
Definition: calcH_MAG.c:12
t27
Definition: calcH_MAG.c:28
static int8_t delta
Definition: RCOutput.cpp:21
Vector3f rngBcnPosSum
Vector3f bcnPosOffsetNED
float bcnPosDownOffsetMax
float minOffsetStateChangeFilt
t12
Definition: calcH_MAG.c:11
float receiverPosCov[3][3]
#define f(i)
T y
Definition: vector3.h:67
t7
Definition: calcH_MAG.c:6
T z
Definition: vector3.h:67
uint8_t stateIndexLim
float bcnPosOffsetMaxVar
struct NavEKF3_core::@152 rngBcnFusionReport[10]
#define HGT_SOURCE_BCN
t14
Definition: calcH_MAG.c:13
float length(void) const
Definition: vector3.cpp:288
bool inhibitDelVelBiasStates
struct nav_filter_status::@138 flags
t23
Definition: calcH_MAG.c:22
t15
Definition: calcH_MAG.c:14
t3
Definition: calcH_MAG.c:2
t8
Definition: calcH_MAG.c:7
t5
Definition: calcH_MAG.c:4
t4
Definition: calcH_MAG.c:3
t25
Definition: calcH_MAG.c:25
bool rngBcnAlignmentCompleted
t29
Definition: calcH_MAG.c:30
t18
Definition: calcH_MAG.c:16
float sq(const T val)
Definition: AP_Math.h:170
t6
Definition: calcH_MAG.c:5
t11
Definition: calcH_MAG.c:10
t32
Definition: calcH_MAG.c:32
t19
Definition: calcH_MAG.c:18
t10
Definition: calcH_MAG.c:9
t20
Definition: calcH_MAG.c:19
t17
Definition: calcH_MAG.c:17
t9
Definition: calcH_MAG.c:8
t30
Definition: calcH_MAG.c:31
NavEKF3 * frontend
nav_filter_status filterStatus
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
t22
Definition: calcH_MAG.c:21
rng_bcn_elements rngBcnDataDelayed
uint32_t imuSampleTime_ms
float bcnPosOffsetMinVar
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
float bcnPosDownOffsetMin
Vector3f receiverPos