APM:Libraries
AP_NavEKF2_PosVelFusion.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>
10 
11 #include <stdio.h>
12 
13 extern const AP_HAL::HAL& hal;
14 
15 /********************************************************
16 * RESET FUNCTIONS *
17 ********************************************************/
18 
19 // Reset velocity states to last GPS measurement if available or to zero if in constant position mode or if PV aiding is not absolute
20 // Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
22 {
23  // Store the position before the reset so that we can record the reset delta
26 
27  // reset the corresponding covariances
28  zeroRows(P,3,4);
29  zeroCols(P,3,4);
30 
31  if (PV_AidingMode != AID_ABSOLUTE) {
33  // set the variances using the measurement noise parameter
34  P[4][4] = P[3][3] = sq(frontend->_gpsHorizVelNoise);
35  } else {
36  // reset horizontal velocity states to the GPS velocity if available
40  // set the variances using the reported GPS speed accuracy
41  P[4][4] = P[3][3] = sq(MAX(frontend->_gpsHorizVelNoise,gpsSpdAccuracy));
42  // clear the timeout flags and counters
43  velTimeout = false;
45  } else {
46  stateStruct.velocity.x = 0.0f;
47  stateStruct.velocity.y = 0.0f;
48  // set the variances using the likely speed range
49  P[4][4] = P[3][3] = sq(25.0f);
50  // clear the timeout flags and counters
51  velTimeout = false;
53  }
54  }
55  for (uint8_t i=0; i<imu_buffer_length; i++) {
56  storedOutput[i].velocity.x = stateStruct.velocity.x;
57  storedOutput[i].velocity.y = stateStruct.velocity.y;
58  }
63 
64  // Calculate the position jump due to the reset
67 
68  // store the time of the reset
70 
71 
72 }
73 
74 // resets position states to last GPS measurement or to zero if in constant position mode
76 {
77  // Store the position before the reset so that we can record the reset delta
80 
81  // reset the corresponding covariances
82  zeroRows(P,6,7);
83  zeroCols(P,6,7);
84 
85  if (PV_AidingMode != AID_ABSOLUTE) {
86  // reset all position state history to the last known position
89  // set the variances using the position measurement noise parameter
90  P[6][6] = P[7][7] = sq(frontend->_gpsHorizPosNoise);
91  } else {
92  // Use GPS data as first preference if fresh data is available
94  // record the ID of the GPS for the data we are using for the reset
96  // write to state vector and compensate for offset between last GPS measurement and the EKF time horizon
99  // set the variances using the position measurement noise parameter
100  P[6][6] = P[7][7] = sq(MAX(gpsPosAccuracy,frontend->_gpsHorizPosNoise));
101  // clear the timeout flags and counters
102  posTimeout = false;
104  } else if (imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250) {
105  // use the range beacon data as a second preference
108  // set the variances from the beacon alignment filter
109  P[6][6] = receiverPosCov[0][0];
110  P[7][7] = receiverPosCov[1][1];
111  // clear the timeout flags and counters
112  rngBcnTimeout = false;
114  } else if (imuSampleTime_ms - extNavDataDelayed.time_ms < 250) {
115  // use the range beacon data as a second preference
118  // set the variances from the beacon alignment filter
119  P[7][7] = P[6][6] = sq(extNavDataDelayed.posErr);
120  }
121  }
122  for (uint8_t i=0; i<imu_buffer_length; i++) {
123  storedOutput[i].position.x = stateStruct.position.x;
124  storedOutput[i].position.y = stateStruct.position.y;
125  }
130 
131  // Calculate the position jump due to the reset
134 
135  // store the time of the reset
137 
138 }
139 
140 // reset the vertical position state using the last height measurement
142 {
143  // Store the position before the reset so that we can record the reset delta
145 
146  // write to the state vector
150 
151  // reset the terrain state height
152  if (onGround) {
153  // assume vehicle is sitting on the ground
155  } else {
156  // can make no assumption other than vehicle is not below ground level
158  }
159  for (uint8_t i=0; i<imu_buffer_length; i++) {
160  storedOutput[i].position.z = stateStruct.position.z;
161  }
162 
163  // Calculate the position jump due to the reset
165 
166  // store the time of the reset
168 
169  // clear the timeout flags and counters
170  hgtTimeout = false;
172 
173  // reset the corresponding covariances
174  zeroRows(P,8,8);
175  zeroCols(P,8,8);
176 
177  // set the variances to the measurement variance
178  P[8][8] = posDownObsNoise;
179 
180  // Reset the vertical velocity state using GPS vertical velocity if we are airborne
181  // Check that GPS vertical velocity data is available and can be used
184  } else if (onGround) {
185  stateStruct.velocity.z = 0.0f;
186  }
187  for (uint8_t i=0; i<imu_buffer_length; i++) {
188  storedOutput[i].velocity.z = stateStruct.velocity.z;
189  }
192 
193  // reset the corresponding covariances
194  zeroRows(P,5,5);
195  zeroCols(P,5,5);
196 
197  // set the variances to the measurement variance
198  P[5][5] = sq(frontend->_gpsVertVelNoise);
199 
200 }
201 
202 // Zero the EKF height datum
203 // Return true if the height datum reset has been performed
205 {
207  // by definition the height datum is at ground level so cannot perform the reset
208  return false;
209  }
210  // record the old height estimate
211  float oldHgt = -stateStruct.position.z;
212  // reset the barometer so that it reads zero at the current height
214  // reset the height state
215  stateStruct.position.z = 0.0f;
216  // adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
217  if (validOrigin) {
218  ekfGpsRefHgt += (double)oldHgt;
219  }
220  // adjust the terrain state
221  terrainState += oldHgt;
222  return true;
223 }
224 
225 /********************************************************
226 * FUSE MEASURED_DATA *
227 ********************************************************/
228 // select fusion of velocity, position and height measurements
230 {
231  // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
232  // If so, don't fuse measurements on this time step to reduce frame over-runs
233  // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
234  if (magFusePerformed && dtIMUavg < 0.005f && !posVelFusionDelayed) {
235  posVelFusionDelayed = true;
236  return;
237  } else {
238  posVelFusionDelayed = false;
239  }
240 
241  // Check for data at the fusion time horizon
243 
244  // read GPS data from the sensor and check for new data in the buffer
245  readGpsData();
247  // Determine if we need to fuse position and velocity data on this time step
249  // set fusion request flags
250  if (frontend->_fusionModeGPS <= 1) {
251  fuseVelData = true;
252  } else {
253  fuseVelData = false;
254  }
255  fusePosData = true;
256  extNavUsedForPos = false;
257 
258  // correct GPS data for position offset of antenna phase centre relative to the IMU
260  if (!posOffsetBody.is_zero()) {
261  // Don't fuse velocity data if GPS doesn't support it
262  if (fuseVelData) {
263  // TODO use a filtered angular rate with a group delay that matches the GPS delay
265  Vector3f velOffsetBody = angRate % posOffsetBody;
266  Vector3f velOffsetEarth = prevTnb.mul_transpose(velOffsetBody);
267  gpsDataDelayed.vel.x -= velOffsetEarth.x;
268  gpsDataDelayed.vel.y -= velOffsetEarth.y;
269  gpsDataDelayed.vel.z -= velOffsetEarth.z;
270  }
271 
272  Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
273  gpsDataDelayed.pos.x -= posOffsetEarth.x;
274  gpsDataDelayed.pos.y -= posOffsetEarth.y;
275  gpsDataDelayed.hgt += posOffsetEarth.z;
276  }
277 
278  // copy corrected GPS data to observation vector
279  if (fuseVelData) {
283  }
286 
287  } else if (extNavDataToFuse && PV_AidingMode == AID_ABSOLUTE) {
288  // This is a special case that uses and external nav system for position
289  extNavUsedForPos = true;
291  fuseVelData = false;
292  fuseHgtData = true;
293  fusePosData = true;
297 
298  // if compass is disabled, also use it for yaw
299  if (!use_compass()) {
300  extNavUsedForYaw = true;
301  if (!yawAlignComplete) {
302  extNavYawResetRequest = true;
303  magYawResetRequest = false;
304  gpsYawResetRequest = false;
306  finalInflightYawInit = true;
307  } else {
308  fuseEulerYaw();
309  }
310  } else {
311  extNavUsedForYaw = false;
312  }
313 
314  } else {
315  fuseVelData = false;
316  fusePosData = false;
317  }
318 
319  // we have GPS data to fuse and a request to align the yaw using the GPS course
320  if (gpsYawResetRequest) {
321  realignYawGPS();
322  }
323 
324  // Select height data to be fused from the available baro, range finder and GPS sources
325 
327 
328  // if we are using GPS, check for a change in receiver and reset position and height
330  // record the ID of the GPS that we are using for the reset
332 
333  // Store the position before the reset so that we can record the reset delta
336 
337  // Set the position states to the position from the new GPS
340 
341  // Calculate the position offset due to the reset
344 
345  // Add the offset to the output observer states
346  for (uint8_t i=0; i<imu_buffer_length; i++) {
347  storedOutput[i].position.x += posResetNE.x;
348  storedOutput[i].position.y += posResetNE.y;
349  }
354 
355  // store the time of the reset
357 
358  // If we are alseo using GPS as the height reference, reset the height
360  // Store the position before the reset so that we can record the reset delta
362 
363  // write to the state vector
365 
366  // Calculate the position jump due to the reset
368 
369  // Add the offset to the output observer states
372  for (uint8_t i=0; i<imu_buffer_length; i++) {
373  storedOutput[i].position.z += posResetD;
374  }
375 
376  // store the time of the reset
378  }
379  }
380 
381  // If we are operating without any aiding, fuse in the last known position
382  // to constrain tilt drift. This assumes a non-manoeuvring vehicle
383  // Do this to coincide with the height fusion
384  if (fuseHgtData && PV_AidingMode == AID_NONE) {
387  fusePosData = true;
388  fuseVelData = false;
389  }
390 
391  // perform fusion
392  if (fuseVelData || fusePosData || fuseHgtData) {
393  FuseVelPosNED();
394  // clear the flags to prevent repeated fusion of the same data
395  fuseVelData = false;
396  fuseHgtData = false;
397  fusePosData = false;
398  }
399 }
400 
401 // fuse selected position, velocity and height measurements
403 {
404  // start performance timer
406 
407  // health is set bad until test passed
408  velHealth = false;
409  posHealth = false;
410  hgtHealth = false;
411 
412  // declare variables used to check measurement errors
413  Vector3f velInnov;
414 
415  // declare variables used to control access to arrays
416  bool fuseData[6] = {false,false,false,false,false,false};
417  uint8_t stateIndex;
418  uint8_t obsIndex;
419 
420  // declare variables used by state and covariance update calculations
421  Vector6 R_OBS; // Measurement variances used for fusion
422  Vector6 R_OBS_DATA_CHECKS; // Measurement variances used for data checks only
423  float SK;
424 
425  // perform sequential fusion of GPS measurements. This assumes that the
426  // errors in the different velocity and position components are
427  // uncorrelated which is not true, however in the absence of covariance
428  // data from the GPS receiver it is the only assumption we can make
429  // so we might as well take advantage of the computational efficiencies
430  // associated with sequential fusion
431  if (fuseVelData || fusePosData || fuseHgtData) {
432 
433  // calculate additional error in GPS position caused by manoeuvring
434  float posErr = frontend->gpsPosVarAccScale * accNavMag;
435 
436  // estimate the GPS Velocity, GPS horiz position and height measurement variances.
437  // Use different errors if operating without external aiding using an assumed position or velocity of zero
438  if (PV_AidingMode == AID_NONE) {
440  // This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate
441  R_OBS[0] = sq(constrain_float(frontend->_noaidHorizNoise, 0.5f, 50.0f));
442  } else {
443  // Use a smaller value to give faster initial alignment
444  R_OBS[0] = sq(0.5f);
445  }
446  R_OBS[1] = R_OBS[0];
447  R_OBS[2] = R_OBS[0];
448  R_OBS[3] = R_OBS[0];
449  R_OBS[4] = R_OBS[0];
450  for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
451  } else {
452  if (gpsSpdAccuracy > 0.0f) {
453  // use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter
456  } else {
457  // calculate additional error in GPS velocity caused by manoeuvring
460  }
461  R_OBS[1] = R_OBS[0];
462  // Use GPS reported position accuracy if available and floor at value set by GPS position noise parameter
463  if (gpsPosAccuracy > 0.0f) {
465  } else {
466  R_OBS[3] = sq(constrain_float(frontend->_gpsHorizPosNoise, 0.1f, 10.0f)) + sq(posErr);
467  }
468  R_OBS[4] = R_OBS[3];
469  // For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity
470  // For horizontal GPs velocity we don't want the acceptance radius to increase with reported GPS accuracy so we use a value based on best GPs perfomrance
471  // plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
472  for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
473  }
474  R_OBS[5] = posDownObsNoise;
475  for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
476 
477  // if vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
478  // innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
479  // the accelerometers and we should disable the GPS and barometer innovation consistency checks.
480  if (useGpsVertVel && fuseVelData && (frontend->_altSource != 2)) {
481  // calculate innovations for height and vertical GPS vel measurements
482  float hgtErr = stateStruct.position.z - velPosObs[5];
483  float velDErr = stateStruct.velocity.z - velPosObs[2];
484  // check if they are the same sign and both more than 3-sigma out of bounds
485  if ((hgtErr*velDErr > 0.0f) && (sq(hgtErr) > 9.0f * (P[8][8] + R_OBS_DATA_CHECKS[5])) && (sq(velDErr) > 9.0f * (P[5][5] + R_OBS_DATA_CHECKS[2]))) {
486  badIMUdata = true;
487  } else {
488  badIMUdata = false;
489  }
490  }
491 
492  // calculate innovations and check GPS data validity using an innovation consistency check
493  // test position measurements
494  if (fusePosData) {
495  // test horizontal position measurements
498  varInnovVelPos[3] = P[6][6] + R_OBS_DATA_CHECKS[3];
499  varInnovVelPos[4] = P[7][7] + R_OBS_DATA_CHECKS[4];
500  // apply an innovation consistency threshold test, but don't fail if bad IMU data
501  float maxPosInnov2 = sq(MAX(0.01f * (float)frontend->_gpsPosInnovGate, 1.0f))*(varInnovVelPos[3] + varInnovVelPos[4]);
502  posTestRatio = (sq(innovVelPos[3]) + sq(innovVelPos[4])) / maxPosInnov2;
503  posHealth = ((posTestRatio < 1.0f) || badIMUdata);
504  // use position data if healthy or timed out
505  if (PV_AidingMode == AID_NONE) {
506  posHealth = true;
508  } else if (posHealth || posTimeout) {
509  posHealth = true;
511  // if timed out or outside the specified uncertainty radius, reset to the GPS
512  if (posTimeout || ((P[6][6] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
513  // reset the position to the current GPS position
514  ResetPosition();
515  // reset the velocity to the GPS velocity
516  ResetVelocity();
517  // don't fuse GPS data on this time step
518  fusePosData = false;
519  fuseVelData = false;
520  // Reset the position variances and corresponding covariances to a value that will pass the checks
521  zeroRows(P,6,7);
522  zeroCols(P,6,7);
523  P[6][6] = sq(float(0.5f*frontend->_gpsGlitchRadiusMax));
524  P[7][7] = P[6][6];
525  // Reset the normalised innovation to avoid failing the bad fusion tests
526  posTestRatio = 0.0f;
527  velTestRatio = 0.0f;
528  }
529  } else {
530  posHealth = false;
531  }
532  }
533 
534  // test velocity measurements
535  if (fuseVelData) {
536  // test velocity measurements
537  uint8_t imax = 2;
538  // Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data
540  imax = 1;
541  }
542  float innovVelSumSq = 0; // sum of squares of velocity innovations
543  float varVelSum = 0; // sum of velocity innovation variances
544  for (uint8_t i = 0; i<=imax; i++) {
545  // velocity states start at index 3
546  stateIndex = i + 3;
547  // calculate innovations using blended and single IMU predicted states
548  velInnov[i] = stateStruct.velocity[i] - velPosObs[i]; // blended
549  // calculate innovation variance
550  varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS_DATA_CHECKS[i];
551  // sum the innovation and innovation variances
552  innovVelSumSq += sq(velInnov[i]);
553  varVelSum += varInnovVelPos[i];
554  }
555  // apply an innovation consistency threshold test, but don't fail if bad IMU data
556  // calculate the test ratio
557  velTestRatio = innovVelSumSq / (varVelSum * sq(MAX(0.01f * (float)frontend->_gpsVelInnovGate, 1.0f)));
558  // fail if the ratio is greater than 1
559  velHealth = ((velTestRatio < 1.0f) || badIMUdata);
560  // use velocity data if healthy, timed out, or in constant position mode
561  if (velHealth || velTimeout) {
562  velHealth = true;
563  // restart the timeout count
565  // If we are doing full aiding and velocity fusion times out, reset to the GPS velocity
567  // reset the velocity to the GPS velocity
568  ResetVelocity();
569  // don't fuse GPS velocity data on this time step
570  fuseVelData = false;
571  // Reset the normalised innovation to avoid failing the bad fusion tests
572  velTestRatio = 0.0f;
573  }
574  } else {
575  velHealth = false;
576  }
577  }
578 
579  // test height measurements
580  if (fuseHgtData) {
581  // calculate height innovations
583  varInnovVelPos[5] = P[8][8] + R_OBS_DATA_CHECKS[5];
584  // calculate the innovation consistency test ratio
585  hgtTestRatio = sq(innovVelPos[5]) / (sq(MAX(0.01f * (float)frontend->_hgtInnovGate, 1.0f)) * varInnovVelPos[5]);
586  // fail if the ratio is > 1, but don't fail if bad IMU data
587  hgtHealth = ((hgtTestRatio < 1.0f) || badIMUdata);
588  // Fuse height data if healthy or timed out or in constant position mode
589  if (hgtHealth || hgtTimeout || (PV_AidingMode == AID_NONE && onGround)) {
590  // Calculate a filtered value to be used by pre-flight health checks
591  // We need to filter because wind gusts can generate significant baro noise and we want to be able to detect bias errors in the inertial solution
592  if (onGround) {
593  float dtBaro = (imuSampleTime_ms - lastHgtPassTime_ms)*1.0e-3f;
594  const float hgtInnovFiltTC = 2.0f;
595  float alpha = constrain_float(dtBaro/(dtBaro+hgtInnovFiltTC),0.0f,1.0f);
597  } else {
598  hgtInnovFiltState = 0.0f;
599  }
600 
601  // if timed out, reset the height
602  if (hgtTimeout) {
603  ResetHeight();
604  }
605 
606  // If we have got this far then declare the height data as healthy and reset the timeout counter
607  hgtHealth = true;
609  }
610  }
611 
612  // set range for sequential fusion of velocity and position measurements depending on which data is available and its health
613  if (fuseVelData && velHealth) {
614  fuseData[0] = true;
615  fuseData[1] = true;
616  if (useGpsVertVel) {
617  fuseData[2] = true;
618  }
619  tiltErrVec.zero();
620  }
621  if (fusePosData && posHealth) {
622  fuseData[3] = true;
623  fuseData[4] = true;
624  tiltErrVec.zero();
625  }
626  if (fuseHgtData && hgtHealth) {
627  fuseData[5] = true;
628  }
629 
630  // fuse measurements sequentially
631  for (obsIndex=0; obsIndex<=5; obsIndex++) {
632  if (fuseData[obsIndex]) {
633  stateIndex = 3 + obsIndex;
634  // calculate the measurement innovation, using states from a different time coordinate if fusing height data
635  // adjust scaling on GPS measurement noise variances if not enough satellites
636  if (obsIndex <= 2)
637  {
639  R_OBS[obsIndex] *= sq(gpsNoiseScaler);
640  }
641  else if (obsIndex == 3 || obsIndex == 4) {
643  R_OBS[obsIndex] *= sq(gpsNoiseScaler);
644  } else if (obsIndex == 5) {
646  const float gndMaxBaroErr = 4.0f;
647  const float gndBaroInnovFloor = -0.5f;
648 
650  // when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
651  // constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
652  // this function looks like this:
653  // |/
654  //---------|---------
655  // ____/|
656  // / |
657  // / |
658  innovVelPos[5] += constrain_float(-innovVelPos[5]+gndBaroInnovFloor, 0.0f, gndBaroInnovFloor+gndMaxBaroErr);
659  }
660  }
661 
662  // calculate the Kalman gain and calculate innovation variances
663  varInnovVelPos[obsIndex] = P[stateIndex][stateIndex] + R_OBS[obsIndex];
664  SK = 1.0f/varInnovVelPos[obsIndex];
665  for (uint8_t i= 0; i<=15; i++) {
666  Kfusion[i] = P[i][stateIndex]*SK;
667  }
668 
669  // inhibit magnetic field state estimation by setting Kalman gains to zero
670  if (!inhibitMagStates) {
671  for (uint8_t i = 16; i<=21; i++) {
672  Kfusion[i] = P[i][stateIndex]*SK;
673  }
674  } else {
675  for (uint8_t i = 16; i<=21; i++) {
676  Kfusion[i] = 0.0f;
677  }
678  }
679 
680  // inhibit wind state estimation by setting Kalman gains to zero
681  if (!inhibitWindStates) {
682  Kfusion[22] = P[22][stateIndex]*SK;
683  Kfusion[23] = P[23][stateIndex]*SK;
684  } else {
685  Kfusion[22] = 0.0f;
686  Kfusion[23] = 0.0f;
687  }
688 
689  // update the covariance - take advantage of direct observation of a single state at index = stateIndex to reduce computations
690  // this is a numerically optimised implementation of standard equation P = (I - K*H)*P;
691  for (uint8_t i= 0; i<=stateIndexLim; i++) {
692  for (uint8_t j= 0; j<=stateIndexLim; j++)
693  {
694  KHP[i][j] = Kfusion[i] * P[stateIndex][j];
695  }
696  }
697  // Check that we are not going to drive any variances negative and skip the update if so
698  bool healthyFusion = true;
699  for (uint8_t i= 0; i<=stateIndexLim; i++) {
700  if (KHP[i][i] > P[i][i]) {
701  healthyFusion = false;
702  }
703  }
704  if (healthyFusion) {
705  // update the covariance matrix
706  for (uint8_t i= 0; i<=stateIndexLim; i++) {
707  for (uint8_t j= 0; j<=stateIndexLim; j++) {
708  P[i][j] = P[i][j] - KHP[i][j];
709  }
710  }
711 
712  // force the covariance matrix to be symmetrical and limit the variances to prevent ill-condiioning.
713  ForceSymmetry();
715 
716  // update the states
717  // zero the attitude error state - by definition it is assumed to be zero before each observaton fusion
719 
720  // calculate state corrections and re-normalise the quaternions for states predicted using the blended IMU data
721  for (uint8_t i = 0; i<=stateIndexLim; i++) {
723  }
724 
725  // the first 3 states represent the angular misalignment vector. This is
726  // is used to correct the estimated quaternion
728 
729  // sum the attitude error from velocity and position fusion only
730  // used as a metric for convergence monitoring
731  if (obsIndex != 5) {
733  }
734  // record good fusion status
735  if (obsIndex == 0) {
736  faultStatus.bad_nvel = false;
737  } else if (obsIndex == 1) {
738  faultStatus.bad_evel = false;
739  } else if (obsIndex == 2) {
740  faultStatus.bad_dvel = false;
741  } else if (obsIndex == 3) {
742  faultStatus.bad_npos = false;
743  } else if (obsIndex == 4) {
744  faultStatus.bad_epos = false;
745  } else if (obsIndex == 5) {
746  faultStatus.bad_dpos = false;
747  }
748  } else {
749  // record bad fusion status
750  if (obsIndex == 0) {
751  faultStatus.bad_nvel = true;
752  } else if (obsIndex == 1) {
753  faultStatus.bad_evel = true;
754  } else if (obsIndex == 2) {
755  faultStatus.bad_dvel = true;
756  } else if (obsIndex == 3) {
757  faultStatus.bad_npos = true;
758  } else if (obsIndex == 4) {
759  faultStatus.bad_epos = true;
760  } else if (obsIndex == 5) {
761  faultStatus.bad_dpos = true;
762  }
763  }
764  }
765  }
766  }
767 
768  // stop performance timer
770 }
771 
772 /********************************************************
773 * MISC FUNCTIONS *
774 ********************************************************/
775 
776 // select the height measurement to be fused from the available baro, range finder and GPS sources
778 {
779  // Read range finder data and check for new data in the buffer
780  // This data is used by both height and optical flow fusion processing
781  readRangeFinder();
783 
784  // correct range data for the body frame position offset relative to the IMU
785  // the corrected reading is the reading that would have been taken if the sensor was
786  // co-located with the IMU
787  if (rangeDataToFuse) {
789  if (sensor != nullptr) {
790  Vector3f posOffsetBody = sensor->get_pos_offset() - accelPosOffset;
791  if (!posOffsetBody.is_zero()) {
792  Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
793  rangeDataDelayed.rng += posOffsetEarth.z / prevTnb.c.z;
794  }
795  }
796  }
797 
798  // read baro height data from the sensor and check for new data in the buffer
799  readBaroData();
801 
802  // select height source
803  if (extNavUsedForPos) {
804  // always use external vision as the hight source if using for position.
806  } else if (((frontend->_useRngSwHgt > 0) || (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
807  if (frontend->_altSource == 1) {
808  // always use range finder
810  } else {
811  // determine if we are above or below the height switch region
812  float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt;
813  bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse;
814  bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse;
815 
816  // If the terrain height is consistent and we are moving slowly, then it can be
817  // used as a height reference in combination with a range finder
818  // apply a hysteresis to the speed check to prevent rapid switching
819  float horizSpeed = norm(stateStruct.velocity.x, stateStruct.velocity.y);
820  bool dontTrustTerrain = ((horizSpeed > frontend->_useRngSwSpd) && filterStatus.flags.horiz_vel) || !terrainHgtStable;
821  float trust_spd_trigger = MAX((frontend->_useRngSwSpd - 1.0f),(frontend->_useRngSwSpd * 0.5f));
822  bool trustTerrain = (horizSpeed < trust_spd_trigger) && terrainHgtStable;
823 
824  /*
825  * Switch between range finder and primary height source using height above ground and speed thresholds with
826  * hysteresis to avoid rapid switching. Using range finder for height requires a consistent terrain height
827  * which cannot be assumed if the vehicle is moving horizontally.
828  */
829  if ((aboveUpperSwHgt || dontTrustTerrain) && (activeHgtSource == HGT_SOURCE_RNG)) {
830  // cannot trust terrain or range finder so stop using range finder height
831  if (frontend->_altSource == 0) {
833  } else if (frontend->_altSource == 2) {
835  }
836  } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) {
837  // reliable terrain and range finder so start using range finder height
839  }
840  }
841  } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) {
843  } else if ((frontend->_altSource == 3) && validOrigin && rngBcnGoodToAlign) {
845  } else {
847  }
848 
849  // Use Baro alt as a fallback if we lose range finder, GPS or external nav
850  bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500));
851  bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000));
852  bool lostExtNavHgt = ((activeHgtSource == HGT_SOURCE_EV) && ((imuSampleTime_ms - extNavMeasTime_ms) > 2000));
853  if (lostRngHgt || lostGpsHgt || lostExtNavHgt) {
855  }
856 
857  // if there is new baro data to fuse, calculate filtered baro data required by other processes
858  if (baroDataToFuse) {
859  // calculate offset to baro data that enables us to switch to Baro height use during operation
862  }
863  // filtered baro data used to provide a reference for takeoff
864  // it is is reset to last height measurement on disarming in performArmingChecks()
865  if (!getTakeoffExpected()) {
866  const float gndHgtFiltTC = 0.5f;
867  const float dtBaro = frontend->hgtAvg_ms*1.0e-3f;
868  float alpha = constrain_float(dtBaro / (dtBaro+gndHgtFiltTC),0.0f,1.0f);
870  }
871  }
872 
873  // If we are not using GPS as the primary height sensor, correct EKF origin height so that
874  // combined local NED position height and origin height remains consistent with the GPS altitude
875  // This also enables the GPS height to be used as a backup height source
876  if (gpsDataToFuse &&
877  (((frontend->_originHgtMode & (1 << 0)) && (activeHgtSource == HGT_SOURCE_BARO)) ||
878  ((frontend->_originHgtMode & (1 << 1)) && (activeHgtSource == HGT_SOURCE_RNG)))
879  ) {
881  }
882 
883  // Select the height measurement source
887  } else if (rangeDataToFuse && (activeHgtSource == HGT_SOURCE_RNG)) {
888  // using range finder data
889  // correct for tilt using a flat earth model
890  if (prevTnb.c.z >= 0.7) {
891  // calculate height above ground
893  // correct for terrain position relative to datum
894  hgtMea -= terrainState;
895  // enable fusion
896  fuseHgtData = true;
897  velPosObs[5] = -hgtMea;
898  // set the observation noise
900  // add uncertainty created by terrain gradient and vehicle tilt
902  } else {
903  // disable fusion if tilted too far
904  fuseHgtData = false;
905  }
906  } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) {
907  // using GPS data
909  // enable fusion
910  velPosObs[5] = -hgtMea;
911  fuseHgtData = true;
912  // set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio
913  if (gpsHgtAccuracy > 0.0f) {
915  } else {
917  }
918  } else if (baroDataToFuse && (activeHgtSource == HGT_SOURCE_BARO)) {
919  // using Baro data
921  // enable fusion
922  velPosObs[5] = -hgtMea;
923  fuseHgtData = true;
924  // set the observation noise
926  // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect
929  }
930  // If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
931  // This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
932  if (motorsArmed && getTakeoffExpected()) {
934  }
935  } else {
936  fuseHgtData = false;
937  }
938 
939  // If we haven't fused height data for a while, then declare the height data as being timed out
940  // set timeout period based on whether we have vertical GPS velocity available to constrain drift
943  hgtTimeout = true;
944  } else {
945  hgtTimeout = false;
946  }
947 }
948 
949 #endif // HAL_CPU_CLASS
uint32_t lastVelReset_ms
Vector2f posResetNE
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
Vector3f tiltErrVec
gps_elements gpsDataDelayed
uint32_t lastVelPassTime_ms
AP_Float _gpsVertVelNoise
Definition: AP_NavEKF2.h:352
ftype Vector6[6]
AP_RangeFinder_Backend * get_backend(uint8_t id) const
AP_Int16 _hgtInnovGate
Definition: AP_NavEKF2.h:370
obs_ring_buffer_t< gps_elements > storedGPS
uint32_t extNavMeasTime_ms
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF2.h:367
Vector3f accelPosOffset
imu_ring_buffer_t< output_elements > storedOutput
bool posVelFusionDelayed
bool extNavYawResetRequest
void update_calibration(void)
Definition: AP_Baro.cpp:246
const uint16_t hgtRetryTimeMode12_ms
Definition: AP_NavEKF2.h:410
uint32_t lastPosReset_ms
gps_elements gpsDataNew
const uint16_t hgtRetryTimeMode0_ms
Definition: AP_NavEKF2.h:409
output_elements outputDataNew
Vector6 varInnovVelPos
NavEKF2 * frontend
AP_Int8 _altSource
Definition: AP_NavEKF2.h:380
Vector28 statesArray
AP_Float _gpsHorizVelNoise
Definition: AP_NavEKF2.h:351
obs_ring_buffer_t< range_elements > storedRange
AP_HAL::Util * util
Definition: HAL.h:115
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
AP_Int8 _useRngSwHgt
Definition: AP_NavEKF2.h:391
uint16_t hgtRetryTime_ms
AP_Int16 _gpsPosInnovGate
Definition: AP_NavEKF2.h:369
float hgtInnovFiltState
#define HGT_SOURCE_RNG
const uint8_t hgtAvg_ms
Definition: AP_NavEKF2.h:415
uint32_t lastHgtPassTime_ms
uint32_t lastTimeGpsReceived_ms
const Vector3f & get_pos_offset() const
struct NavEKF2_core::state_elements & stateStruct
const float gpsDVelVarAccScale
Definition: AP_NavEKF2.h:402
const RangeFinder & _rng
Definition: AP_NavEKF2.h:344
uint32_t imuSampleTime_ms
bool inhibitGpsVertVelUse
Definition: AP_NavEKF2.h:462
output_elements outputDataDelayed
AP_Int16 _gpsVelInnovGate
Definition: AP_NavEKF2.h:368
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
imu_elements imuDataDelayed
AP_Float _baroAltNoise
Definition: AP_NavEKF2.h:354
T y
Definition: vector2.h:37
const float gndEffectBaroScaler
Definition: AP_NavEKF2.h:424
baro_elements baroDataDelayed
float receiverPosCov[3][3]
const Vector3f & get_antenna_offset(uint8_t instance) const
Definition: AP_GPS.cpp:1137
struct NavEKF2_core::@145 faultStatus
AP_Float _terrGradMax
Definition: AP_NavEKF2.h:392
const float gpsPosVarAccScale
Definition: AP_NavEKF2.h:403
#define HGT_SOURCE_EV
#define f(i)
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
AP_Float _gpsHorizPosNoise
Definition: AP_NavEKF2.h:353
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
T z
Definition: vector3.h:67
int16_t max_distance_cm_orient(enum Rotation orientation) const
uint8_t activeHgtSource
uint32_t rngBcnLast3DmeasTime_ms
Vector6 innovVelPos
#define HGT_SOURCE_BCN
#define HGT_SOURCE_BARO
Matrix3f prevTnb
bool use_compass(void) const
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
struct nav_filter_status::@138 flags
#define HGT_SOURCE_GPS
obs_ring_buffer_t< baro_elements > storedBaro
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
nav_filter_status filterStatus
ext_nav_elements extNavDataDelayed
AP_Float _noaidHorizNoise
Definition: AP_NavEKF2.h:386
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
uint32_t lastRngBcnPassTime_ms
AP_Float _rngNoise
Definition: AP_NavEKF2.h:382
uint8_t last_gps_idx
uint8_t stateIndexLim
Vector2f velResetNE
const float gpsNEVelVarAccScale
Definition: AP_NavEKF2.h:401
float sq(const T val)
Definition: AP_Math.h:170
bool is_zero(void) const
Definition: vector3.h:159
obs_ring_buffer_t< ext_nav_elements > storedExtNav
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
void rotate(const Vector3f &v)
Definition: quaternion.cpp:182
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
AP_Float _useRngSwSpd
Definition: AP_NavEKF2.h:396
AP_Baro & baro()
Definition: AP_Baro.cpp:737
range_elements rangeDataDelayed
uint32_t lastPosPassTime_ms
uint32_t rngValidMeaTime_ms
AP_Int8 _gpsGlitchRadiusMax
Definition: AP_NavEKF2.h:374
AP_Int8 _originHgtMode
Definition: AP_NavEKF2.h:398
uint8_t imu_buffer_length
Vector3f receiverPos
Vector2f lastKnownPositionNE
void zero()
Definition: vector3.h:182
Vector28 Kfusion
AidingMode PV_AidingMode
T x
Definition: vector3.h:67
uint32_t lastPosResetD_ms