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