APM:Libraries
AP_NavEKF3_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_NavEKF3.h"
6 #include "AP_NavEKF3_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 #include <GCS_MAVLink/GCS.h>
11 
12 extern const AP_HAL::HAL& hal;
13 
14 /********************************************************
15 * RESET FUNCTIONS *
16 ********************************************************/
17 
18 // Reset velocity states to last GPS measurement if available or to zero if in constant position mode or if PV aiding is not absolute
19 // Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
21 {
22  // Store the position before the reset so that we can record the reset delta
25 
26  // reset the corresponding covariances
27  zeroRows(P,4,5);
28  zeroCols(P,4,5);
29 
30  if (PV_AidingMode != AID_ABSOLUTE) {
32  // set the variances using the measurement noise parameter
33  P[5][5] = P[4][4] = sq(frontend->_gpsHorizVelNoise);
34  } else {
35  // reset horizontal velocity states to the GPS velocity if available
39  // set the variances using the reported GPS speed accuracy
40  P[5][5] = P[4][4] = sq(MAX(frontend->_gpsHorizVelNoise,gpsSpdAccuracy));
41  // clear the timeout flags and counters
42  velTimeout = false;
44  } else {
45  stateStruct.velocity.x = 0.0f;
46  stateStruct.velocity.y = 0.0f;
47  // set the variances using the likely speed range
48  P[5][5] = P[4][4] = sq(25.0f);
49  // clear the timeout flags and counters
50  velTimeout = false;
52  }
53  }
54  for (uint8_t i=0; i<imu_buffer_length; i++) {
55  storedOutput[i].velocity.x = stateStruct.velocity.x;
56  storedOutput[i].velocity.y = stateStruct.velocity.y;
57  }
62 
63  // Calculate the position jump due to the reset
66 
67  // store the time of the reset
69 
70  // clear reset data source preference
72 
73 }
74 
75 // resets position states to last GPS measurement or to zero if in constant position mode
77 {
78  // Store the position before the reset so that we can record the reset delta
81 
82  // reset the corresponding covariances
83  zeroRows(P,7,8);
84  zeroCols(P,7,8);
85 
86  if (PV_AidingMode != AID_ABSOLUTE) {
87  // reset all position state history to the last known position
90  // set the variances using the position measurement noise parameter
91  P[7][7] = P[8][8] = sq(frontend->_gpsHorizPosNoise);
92  } else {
93  // Use GPS data as first preference if fresh data is available
95  // record the ID of the GPS for the data we are using for the reset
97  // write to state vector and compensate for offset between last GPS measurement and the EKF time horizon
100  // set the variances using the position measurement noise parameter
101  P[7][7] = P[8][8] = sq(MAX(gpsPosAccuracy,frontend->_gpsHorizPosNoise));
102  // clear the timeout flags and counters
103  posTimeout = false;
106  // use the range beacon data as a second preference
109  // set the variances from the beacon alignment filter
110  P[7][7] = receiverPosCov[0][0];
111  P[8][8] = receiverPosCov[1][1];
112  // clear the timeout flags and counters
113  rngBcnTimeout = false;
115  }
116  }
117  for (uint8_t i=0; i<imu_buffer_length; i++) {
118  storedOutput[i].position.x = stateStruct.position.x;
119  storedOutput[i].position.y = stateStruct.position.y;
120  }
125 
126  // Calculate the position jump due to the reset
129 
130  // store the time of the reset
132 
133  // clear reset source preference
135 
136 }
137 
138 // reset the vertical position state using the last height measurement
140 {
141  // Store the position before the reset so that we can record the reset delta
143 
144  // write to the state vector
148 
149  // reset the terrain state height
150  if (onGround) {
151  // assume vehicle is sitting on the ground
153  } else {
154  // can make no assumption other than vehicle is not below ground level
156  }
157  for (uint8_t i=0; i<imu_buffer_length; i++) {
158  storedOutput[i].position.z = stateStruct.position.z;
159  }
160 
161  // Calculate the position jump due to the reset
163 
164  // store the time of the reset
166 
167  // clear the timeout flags and counters
168  hgtTimeout = false;
170 
171  // reset the corresponding covariances
172  zeroRows(P,9,9);
173  zeroCols(P,9,9);
174 
175  // set the variances to the measurement variance
176  P[9][9] = posDownObsNoise;
177 
178  // Reset the vertical velocity state using GPS vertical velocity if we are airborne
179  // Check that GPS vertical velocity data is available and can be used
182  } else if (onGround) {
183  stateStruct.velocity.z = 0.0f;
184  }
185  for (uint8_t i=0; i<imu_buffer_length; i++) {
186  storedOutput[i].velocity.z = stateStruct.velocity.z;
187  }
190 
191  // reset the corresponding covariances
192  zeroRows(P,6,6);
193  zeroCols(P,6,6);
194 
195  // set the variances to the measurement variance
196  P[6][6] = sq(frontend->_gpsVertVelNoise);
197 
198 }
199 
200 // Zero the EKF height datum
201 // Return true if the height datum reset has been performed
203 {
205  // by definition the height datum is at ground level so cannot perform the reset
206  return false;
207  }
208  // record the old height estimate
209  float oldHgt = -stateStruct.position.z;
210  // reset the barometer so that it reads zero at the current height
212  // reset the height state
213  stateStruct.position.z = 0.0f;
214  // adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
215  if (validOrigin) {
216  ekfGpsRefHgt += (double)oldHgt;
217  }
218  // adjust the terrain state
219  terrainState += oldHgt;
220  return true;
221 }
222 
223 /********************************************************
224 * FUSE MEASURED_DATA *
225 ********************************************************/
226 // select fusion of velocity, position and height measurements
228 {
229  // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
230  // If so, don't fuse measurements on this time step to reduce frame over-runs
231  // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
232  if (magFusePerformed && dtIMUavg < 0.005f && !posVelFusionDelayed) {
233  posVelFusionDelayed = true;
234  return;
235  } else {
236  posVelFusionDelayed = false;
237  }
238 
239  // read GPS data from the sensor and check for new data in the buffer
240  readGpsData();
242  // Determine if we need to fuse position and velocity data on this time step
244  // correct GPS data for position offset of antenna phase centre relative to the IMU
246  if (!posOffsetBody.is_zero()) {
247  if (fuseVelData) {
248  // TODO use a filtered angular rate with a group delay that matches the GPS delay
250  Vector3f velOffsetBody = angRate % posOffsetBody;
251  Vector3f velOffsetEarth = prevTnb.mul_transpose(velOffsetBody);
252  gpsDataDelayed.vel -= velOffsetEarth;
253  }
254  Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
255  gpsDataDelayed.pos.x -= posOffsetEarth.x;
256  gpsDataDelayed.pos.y -= posOffsetEarth.y;
257  gpsDataDelayed.hgt += posOffsetEarth.z;
258  }
259 
260 
261  // Don't fuse velocity data if GPS doesn't support it
262  if (frontend->_fusionModeGPS <= 1) {
263  fuseVelData = true;
264  } else {
265  fuseVelData = false;
266  }
267  fusePosData = true;
268 
269  } else {
270  fuseVelData = false;
271  fusePosData = false;
272  }
273 
274  // we have GPS data to fuse and a request to align the yaw using the GPS course
275  if (gpsYawResetRequest) {
276  realignYawGPS();
277  }
278 
279  // Select height data to be fused from the available baro, range finder and GPS sources
281 
282  // if we are using GPS, check for a change in receiver and reset position and height
284  // record the ID of the GPS that we are using for the reset
286 
287  // Store the position before the reset so that we can record the reset delta
290 
291  // Set the position states to the position from the new GPS
294 
295  // Calculate the position offset due to the reset
298 
299  // Add the offset to the output observer states
300  for (uint8_t i=0; i<imu_buffer_length; i++) {
301  storedOutput[i].position.x += posResetNE.x;
302  storedOutput[i].position.y += posResetNE.y;
303  }
308 
309  // store the time of the reset
311 
312  // If we are alseo using GPS as the height reference, reset the height
314  // Store the position before the reset so that we can record the reset delta
316 
317  // write to the state vector
319 
320  // Calculate the position jump due to the reset
322 
323  // Add the offset to the output observer states
326  for (uint8_t i=0; i<imu_buffer_length; i++) {
327  storedOutput[i].position.z += posResetD;
328  }
329 
330  // store the time of the reset
332  }
333  }
334 
335  // If we are operating without any aiding, fuse in the last known position
336  // to constrain tilt drift. This assumes a non-manoeuvring vehicle
337  // Do this to coincide with the height fusion
338  if (fuseHgtData && PV_AidingMode == AID_NONE) {
342 
343  fusePosData = true;
344  fuseVelData = false;
345  }
346 
347  // perform fusion
348  if (fuseVelData || fusePosData || fuseHgtData) {
349  FuseVelPosNED();
350  // clear the flags to prevent repeated fusion of the same data
351  fuseVelData = false;
352  fuseHgtData = false;
353  fusePosData = false;
354  }
355 }
356 
357 // fuse selected position, velocity and height measurements
359 {
360  // start performance timer
362 
363  // health is set bad until test passed
364  velHealth = false;
365  posHealth = false;
366  hgtHealth = false;
367 
368  // declare variables used to check measurement errors
369  Vector3f velInnov;
370 
371  // declare variables used to control access to arrays
372  bool fuseData[6] = {false,false,false,false,false,false};
373  uint8_t stateIndex;
374  uint8_t obsIndex;
375 
376  // declare variables used by state and covariance update calculations
377  Vector6 R_OBS; // Measurement variances used for fusion
378  Vector6 R_OBS_DATA_CHECKS; // Measurement variances used for data checks only
379  Vector6 observation;
380  float SK;
381 
382  // perform sequential fusion of GPS measurements. This assumes that the
383  // errors in the different velocity and position components are
384  // uncorrelated which is not true, however in the absence of covariance
385  // data from the GPS receiver it is the only assumption we can make
386  // so we might as well take advantage of the computational efficiencies
387  // associated with sequential fusion
388  if (fuseVelData || fusePosData || fuseHgtData) {
389  // form the observation vector
390  observation[0] = gpsDataDelayed.vel.x;
391  observation[1] = gpsDataDelayed.vel.y;
392  observation[2] = gpsDataDelayed.vel.z;
393  observation[3] = gpsDataDelayed.pos.x;
394  observation[4] = gpsDataDelayed.pos.y;
395  observation[5] = -hgtMea;
396 
397  // calculate additional error in GPS position caused by manoeuvring
398  float posErr = frontend->gpsPosVarAccScale * accNavMag;
399 
400  // estimate the GPS Velocity, GPS horiz position and height measurement variances.
401  // Use different errors if operating without external aiding using an assumed position or velocity of zero
402  if (PV_AidingMode == AID_NONE) {
404  // This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate
405  R_OBS[0] = sq(constrain_float(frontend->_noaidHorizNoise, 0.5f, 50.0f));
406  } else {
407  // Use a smaller value to give faster initial alignment
408  R_OBS[0] = sq(0.5f);
409  }
410  R_OBS[1] = R_OBS[0];
411  R_OBS[2] = R_OBS[0];
412  R_OBS[3] = R_OBS[0];
413  R_OBS[4] = R_OBS[0];
414  for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
415  } else {
416  if (gpsSpdAccuracy > 0.0f) {
417  // use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter
420  } else {
421  // calculate additional error in GPS velocity caused by manoeuvring
424  }
425  R_OBS[1] = R_OBS[0];
426  // Use GPS reported position accuracy if available and floor at value set by GPS position noise parameter
427  if (gpsPosAccuracy > 0.0f) {
429  } else {
430  R_OBS[3] = sq(constrain_float(frontend->_gpsHorizPosNoise, 0.1f, 10.0f)) + sq(posErr);
431  }
432  R_OBS[4] = R_OBS[3];
433  // For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity
434  // 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
435  // plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
436  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);
437  }
438  R_OBS[5] = posDownObsNoise;
439  for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
440 
441  // if vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
442  // innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
443  // the accelerometers and we should disable the GPS and barometer innovation consistency checks.
444  if (useGpsVertVel && fuseVelData && (frontend->_altSource != 2)) {
445  // calculate innovations for height and vertical GPS vel measurements
446  float hgtErr = stateStruct.position.z - observation[5];
447  float velDErr = stateStruct.velocity.z - observation[2];
448  // check if they are the same sign and both more than 3-sigma out of bounds
449  if ((hgtErr*velDErr > 0.0f) && (sq(hgtErr) > 9.0f * (P[9][9] + R_OBS_DATA_CHECKS[5])) && (sq(velDErr) > 9.0f * (P[6][6] + R_OBS_DATA_CHECKS[2]))) {
450  badIMUdata = true;
451  } else {
452  badIMUdata = false;
453  }
454  }
455 
456  // calculate innovations and check GPS data validity using an innovation consistency check
457  // test position measurements
458  if (fusePosData) {
459  // test horizontal position measurements
460  innovVelPos[3] = stateStruct.position.x - observation[3];
461  innovVelPos[4] = stateStruct.position.y - observation[4];
462  varInnovVelPos[3] = P[7][7] + R_OBS_DATA_CHECKS[3];
463  varInnovVelPos[4] = P[8][8] + R_OBS_DATA_CHECKS[4];
464  // apply an innovation consistency threshold test, but don't fail if bad IMU data
465  float maxPosInnov2 = sq(MAX(0.01f * (float)frontend->_gpsPosInnovGate, 1.0f))*(varInnovVelPos[3] + varInnovVelPos[4]);
466  posTestRatio = (sq(innovVelPos[3]) + sq(innovVelPos[4])) / maxPosInnov2;
467  posHealth = ((posTestRatio < 1.0f) || badIMUdata);
468  // use position data if healthy or timed out
469  if (PV_AidingMode == AID_NONE) {
470  posHealth = true;
472  } else if (posHealth || posTimeout) {
473  posHealth = true;
475  // if timed out or outside the specified uncertainty radius, reset to the GPS
476  if (posTimeout || ((P[8][8] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
477  // reset the position to the current GPS position
478  ResetPosition();
479  // reset the velocity to the GPS velocity
480  ResetVelocity();
481  // don't fuse GPS data on this time step
482  fusePosData = false;
483  fuseVelData = false;
484  // Reset the position variances and corresponding covariances to a value that will pass the checks
485  zeroRows(P,7,8);
486  zeroCols(P,7,8);
487  P[7][7] = sq(float(0.5f*frontend->_gpsGlitchRadiusMax));
488  P[8][8] = P[7][7];
489  // Reset the normalised innovation to avoid failing the bad fusion tests
490  posTestRatio = 0.0f;
491  velTestRatio = 0.0f;
492  }
493  } else {
494  posHealth = false;
495  }
496  }
497 
498  // test velocity measurements
499  if (fuseVelData) {
500  // test velocity measurements
501  uint8_t imax = 2;
502  // Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data
504  imax = 1;
505  }
506  float innovVelSumSq = 0; // sum of squares of velocity innovations
507  float varVelSum = 0; // sum of velocity innovation variances
508  for (uint8_t i = 0; i<=imax; i++) {
509  // velocity states start at index 4
510  stateIndex = i + 4;
511  // calculate innovations using blended and single IMU predicted states
512  velInnov[i] = stateStruct.velocity[i] - observation[i]; // blended
513  // calculate innovation variance
514  varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS_DATA_CHECKS[i];
515  // sum the innovation and innovation variances
516  innovVelSumSq += sq(velInnov[i]);
517  varVelSum += varInnovVelPos[i];
518  }
519  // apply an innovation consistency threshold test, but don't fail if bad IMU data
520  // calculate the test ratio
521  velTestRatio = innovVelSumSq / (varVelSum * sq(MAX(0.01f * (float)frontend->_gpsVelInnovGate, 1.0f)));
522  // fail if the ratio is greater than 1
523  velHealth = ((velTestRatio < 1.0f) || badIMUdata);
524  // use velocity data if healthy, timed out, or in constant position mode
525  if (velHealth || velTimeout) {
526  velHealth = true;
527  // restart the timeout count
529  // If we are doing full aiding and velocity fusion times out, reset to the GPS velocity
531  // reset the velocity to the GPS velocity
532  ResetVelocity();
533  // don't fuse GPS velocity data on this time step
534  fuseVelData = false;
535  // Reset the normalised innovation to avoid failing the bad fusion tests
536  velTestRatio = 0.0f;
537  }
538  } else {
539  velHealth = false;
540  }
541  }
542 
543  // test height measurements
544  if (fuseHgtData) {
545  // calculate height innovations
546  innovVelPos[5] = stateStruct.position.z - observation[5];
547  varInnovVelPos[5] = P[9][9] + R_OBS_DATA_CHECKS[5];
548  // calculate the innovation consistency test ratio
549  hgtTestRatio = sq(innovVelPos[5]) / (sq(MAX(0.01f * (float)frontend->_hgtInnovGate, 1.0f)) * varInnovVelPos[5]);
550  // fail if the ratio is > 1, but don't fail if bad IMU data
551  hgtHealth = ((hgtTestRatio < 1.0f) || badIMUdata);
552  // Fuse height data if healthy or timed out or in constant position mode
553  if (hgtHealth || hgtTimeout || (PV_AidingMode == AID_NONE && onGround)) {
554  // Calculate a filtered value to be used by pre-flight health checks
555  // 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
556  if (onGround) {
557  float dtBaro = (imuSampleTime_ms - lastHgtPassTime_ms)*1.0e-3f;
558  const float hgtInnovFiltTC = 2.0f;
559  float alpha = constrain_float(dtBaro/(dtBaro+hgtInnovFiltTC),0.0f,1.0f);
561  } else {
562  hgtInnovFiltState = 0.0f;
563  }
564 
565  // if timed out, reset the height
566  if (hgtTimeout) {
567  ResetHeight();
568  }
569 
570  // If we have got this far then declare the height data as healthy and reset the timeout counter
571  hgtHealth = true;
573  }
574  }
575 
576  // set range for sequential fusion of velocity and position measurements depending on which data is available and its health
577  if (fuseVelData && velHealth) {
578  fuseData[0] = true;
579  fuseData[1] = true;
580  if (useGpsVertVel) {
581  fuseData[2] = true;
582  }
583  }
584  if (fusePosData && posHealth) {
585  fuseData[3] = true;
586  fuseData[4] = true;
587  }
588  if (fuseHgtData && hgtHealth) {
589  fuseData[5] = true;
590  }
591 
592  // fuse measurements sequentially
593  for (obsIndex=0; obsIndex<=5; obsIndex++) {
594  if (fuseData[obsIndex]) {
595  stateIndex = 4 + obsIndex;
596  // calculate the measurement innovation, using states from a different time coordinate if fusing height data
597  // adjust scaling on GPS measurement noise variances if not enough satellites
598  if (obsIndex <= 2)
599  {
601  R_OBS[obsIndex] *= sq(gpsNoiseScaler);
602  }
603  else if (obsIndex == 3 || obsIndex == 4) {
604  innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - observation[obsIndex];
605  R_OBS[obsIndex] *= sq(gpsNoiseScaler);
606  } else if (obsIndex == 5) {
607  innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - observation[obsIndex];
608  const float gndMaxBaroErr = 4.0f;
609  const float gndBaroInnovFloor = -0.5f;
610 
612  // when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
613  // constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
614  // this function looks like this:
615  // |/
616  //---------|---------
617  // ____/|
618  // / |
619  // / |
620  innovVelPos[5] += constrain_float(-innovVelPos[5]+gndBaroInnovFloor, 0.0f, gndBaroInnovFloor+gndMaxBaroErr);
621  }
622  }
623 
624  // calculate the Kalman gain and calculate innovation variances
625  varInnovVelPos[obsIndex] = P[stateIndex][stateIndex] + R_OBS[obsIndex];
626  SK = 1.0f/varInnovVelPos[obsIndex];
627  for (uint8_t i= 0; i<=9; i++) {
628  Kfusion[i] = P[i][stateIndex]*SK;
629  }
630 
631  // inhibit delta angle bias state estmation by setting Kalman gains to zero
633  for (uint8_t i = 10; i<=12; i++) {
634  Kfusion[i] = P[i][stateIndex]*SK;
635  }
636  } else {
637  // zero indexes 10 to 12 = 3*4 bytes
638  memset(&Kfusion[10], 0, 12);
639  }
640 
641  // inhibit delta velocity bias state estmation by setting Kalman gains to zero
643  for (uint8_t i = 13; i<=15; i++) {
644  Kfusion[i] = P[i][stateIndex]*SK;
645  }
646  } else {
647  // zero indexes 13 to 15 = 3*4 bytes
648  memset(&Kfusion[13], 0, 12);
649  }
650 
651  // inhibit magnetic field state estimation by setting Kalman gains to zero
652  if (!inhibitMagStates) {
653  for (uint8_t i = 16; i<=21; i++) {
654  Kfusion[i] = P[i][stateIndex]*SK;
655  }
656  } else {
657  // zero indexes 16 to 21 = 6*4 bytes
658  memset(&Kfusion[16], 0, 24);
659  }
660 
661  // inhibit wind state estimation by setting Kalman gains to zero
662  if (!inhibitWindStates) {
663  Kfusion[22] = P[22][stateIndex]*SK;
664  Kfusion[23] = P[23][stateIndex]*SK;
665  } else {
666  // zero indexes 22 to 23 = 2*4 bytes
667  memset(&Kfusion[22], 0, 8);
668  }
669 
670  // update the covariance - take advantage of direct observation of a single state at index = stateIndex to reduce computations
671  // this is a numerically optimised implementation of standard equation P = (I - K*H)*P;
672  for (uint8_t i= 0; i<=stateIndexLim; i++) {
673  for (uint8_t j= 0; j<=stateIndexLim; j++)
674  {
675  KHP[i][j] = Kfusion[i] * P[stateIndex][j];
676  }
677  }
678  // Check that we are not going to drive any variances negative and skip the update if so
679  bool healthyFusion = true;
680  for (uint8_t i= 0; i<=stateIndexLim; i++) {
681  if (KHP[i][i] > P[i][i]) {
682  healthyFusion = false;
683  }
684  }
685  if (healthyFusion) {
686  // update the covariance matrix
687  for (uint8_t i= 0; i<=stateIndexLim; i++) {
688  for (uint8_t j= 0; j<=stateIndexLim; j++) {
689  P[i][j] = P[i][j] - KHP[i][j];
690  }
691  }
692 
693  // force the covariance matrix to be symmetrical and limit the variances to prevent ill-condiioning.
694  ForceSymmetry();
696 
697  // update states and renormalise the quaternions
698  for (uint8_t i = 0; i<=stateIndexLim; i++) {
700  }
702 
703  // record good fusion status
704  if (obsIndex == 0) {
705  faultStatus.bad_nvel = false;
706  } else if (obsIndex == 1) {
707  faultStatus.bad_evel = false;
708  } else if (obsIndex == 2) {
709  faultStatus.bad_dvel = false;
710  } else if (obsIndex == 3) {
711  faultStatus.bad_npos = false;
712  } else if (obsIndex == 4) {
713  faultStatus.bad_epos = false;
714  } else if (obsIndex == 5) {
715  faultStatus.bad_dpos = false;
716  }
717  } else {
718  // record bad fusion status
719  if (obsIndex == 0) {
720  faultStatus.bad_nvel = true;
721  } else if (obsIndex == 1) {
722  faultStatus.bad_evel = true;
723  } else if (obsIndex == 2) {
724  faultStatus.bad_dvel = true;
725  } else if (obsIndex == 3) {
726  faultStatus.bad_npos = true;
727  } else if (obsIndex == 4) {
728  faultStatus.bad_epos = true;
729  } else if (obsIndex == 5) {
730  faultStatus.bad_dpos = true;
731  }
732  }
733  }
734  }
735  }
736 
737  // stop performance timer
739 }
740 
741 /********************************************************
742 * MISC FUNCTIONS *
743 ********************************************************/
744 
745 // select the height measurement to be fused from the available baro, range finder and GPS sources
747 {
748  // Read range finder data and check for new data in the buffer
749  // This data is used by both height and optical flow fusion processing
750  readRangeFinder();
752 
753  // correct range data for the body frame position offset relative to the IMU
754  // the corrected reading is the reading that would have been taken if the sensor was
755  // co-located with the IMU
756  if (rangeDataToFuse) {
758  if (sensor != nullptr) {
759  Vector3f posOffsetBody = sensor->get_pos_offset() - accelPosOffset;
760  if (!posOffsetBody.is_zero()) {
761  Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
762  rangeDataDelayed.rng += posOffsetEarth.z / prevTnb.c.z;
763  }
764  }
765  }
766 
767  // read baro height data from the sensor and check for new data in the buffer
768  readBaroData();
770 
771  // select height source
772  if (((frontend->_useRngSwHgt > 0) || (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
773  if (frontend->_altSource == 1) {
774  // always use range finder
776  } else {
777  // determine if we are above or below the height switch region
778  float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt;
779  bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse;
780  bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse;
781 
782  // If the terrain height is consistent and we are moving slowly, then it can be
783  // used as a height reference in combination with a range finder
784  // apply a hysteresis to the speed check to prevent rapid switching
785  bool dontTrustTerrain, trustTerrain;
787  // We can use the velocity estimate
788  float horizSpeed = norm(stateStruct.velocity.x, stateStruct.velocity.y);
789  dontTrustTerrain = (horizSpeed > frontend->_useRngSwSpd) || !terrainHgtStable;
790  float trust_spd_trigger = MAX((frontend->_useRngSwSpd - 1.0f),(frontend->_useRngSwSpd * 0.5f));
791  trustTerrain = (horizSpeed < trust_spd_trigger) && terrainHgtStable;
792  } else {
793  // We can't use the velocity estimate
794  dontTrustTerrain = !terrainHgtStable;
795  trustTerrain = terrainHgtStable;
796  }
797 
798  /*
799  * Switch between range finder and primary height source using height above ground and speed thresholds with
800  * hysteresis to avoid rapid switching. Using range finder for height requires a consistent terrain height
801  * which cannot be assumed if the vehicle is moving horizontally.
802  */
803  if ((aboveUpperSwHgt || dontTrustTerrain) && (activeHgtSource == HGT_SOURCE_RNG)) {
804  // cannot trust terrain or range finder so stop using range finder height
805  if (frontend->_altSource == 0) {
807  } else if (frontend->_altSource == 2) {
809  }
810  } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) {
811  // reliable terrain and range finder so start using range finder height
813  }
814  }
815  } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) {
817  } else if ((frontend->_altSource == 3) && validOrigin && rngBcnGoodToAlign) {
819  } else {
821  }
822 
823  // Use Baro alt as a fallback if we lose range finder or GPS
824  bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500));
825  bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000));
826  if (lostRngHgt || lostGpsHgt) {
828  }
829 
830  // if there is new baro data to fuse, calculate filtered baro data required by other processes
831  if (baroDataToFuse) {
832  // calculate offset to baro data that enables us to switch to Baro height use during operation
835  }
836  // filtered baro data used to provide a reference for takeoff
837  // it is is reset to last height measurement on disarming in performArmingChecks()
838  if (!getTakeoffExpected()) {
839  const float gndHgtFiltTC = 0.5f;
840  const float dtBaro = frontend->hgtAvg_ms*1.0e-3f;
841  float alpha = constrain_float(dtBaro / (dtBaro+gndHgtFiltTC),0.0f,1.0f);
843  }
844  }
845 
846  // If we are not using GPS as the primary height sensor, correct EKF origin height so that
847  // combined local NED position height and origin height remains consistent with the GPS altitude
848  // This also enables the GPS height to be used as a backup height source
849  if (gpsDataToFuse &&
850  (((frontend->_originHgtMode & (1 << 0)) && (activeHgtSource == HGT_SOURCE_BARO)) ||
851  ((frontend->_originHgtMode & (1 << 1)) && (activeHgtSource == HGT_SOURCE_RNG)))
852  ) {
854  }
855 
856  // Select the height measurement source
858  // using range finder data
859  // correct for tilt using a flat earth model
860  if (prevTnb.c.z >= 0.7) {
861  // calculate height above ground
863  // correct for terrain position relative to datum
864  hgtMea -= terrainState;
865  // enable fusion
866  fuseHgtData = true;
867  // set the observation noise
869  // add uncertainty created by terrain gradient and vehicle tilt
871  } else {
872  // disable fusion if tilted too far
873  fuseHgtData = false;
874  }
875  } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) {
876  // using GPS data
878  // enable fusion
879  fuseHgtData = true;
880  // set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio
881  if (gpsHgtAccuracy > 0.0f) {
883  } else {
885  }
886  } else if (baroDataToFuse && (activeHgtSource == HGT_SOURCE_BARO)) {
887  // using Baro data
889  // enable fusion
890  fuseHgtData = true;
891  // set the observation noise
893  // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect
896  }
897  // If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
898  // This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
899  if (motorsArmed && getTakeoffExpected()) {
901  }
902  } else {
903  fuseHgtData = false;
904  }
905 
906  // If we haven't fused height data for a while, then declare the height data as being timed out
907  // set timeout period based on whether we have vertical GPS velocity available to constrain drift
910  hgtTimeout = true;
911  } else {
912  hgtTimeout = false;
913  }
914 }
915 
916 /*
917  * Fuse body frame velocity measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
918  * The script file used to generate these and other equations in this filter can be found here:
919  * https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
920 */
922 {
923  Vector24 H_VEL;
924  Vector3f bodyVelPred;
925 
926  // Copy required states to local variable names
927  float q0 = stateStruct.quat[0];
928  float q1 = stateStruct.quat[1];
929  float q2 = stateStruct.quat[2];
930  float q3 = stateStruct.quat[3];
931  float vn = stateStruct.velocity.x;
932  float ve = stateStruct.velocity.y;
933  float vd = stateStruct.velocity.z;
934 
935  // Fuse X, Y and Z axis measurements sequentially assuming observation errors are uncorrelated
936  for (uint8_t obsIndex=0; obsIndex<=2; obsIndex++) {
937 
938  // calculate relative velocity in sensor frame including the relative motion due to rotation
939  bodyVelPred = (prevTnb * stateStruct.velocity);
940 
941  // correct sensor offset body frame position offset relative to IMU
943 
944  // correct prediction for relative motion due to rotation
945  // note - % operator overloaded for cross product
946  if (imuDataDelayed.delAngDT > 0.001f) {
947  bodyVelPred += (imuDataDelayed.delAng * (1.0f / imuDataDelayed.delAngDT)) % posOffsetBody;
948  }
949 
950  // calculate observation jacobians and Kalman gains
951  if (obsIndex == 0) {
952  // calculate X axis observation Jacobian
953  H_VEL[0] = q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f;
954  H_VEL[1] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
955  H_VEL[2] = q0*vd*-2.0f+q1*ve*2.0f-q2*vn*2.0f;
956  H_VEL[3] = q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f;
957  H_VEL[4] = q0*q0+q1*q1-q2*q2-q3*q3;
958  H_VEL[5] = q0*q3*2.0f+q1*q2*2.0f;
959  H_VEL[6] = q0*q2*-2.0f+q1*q3*2.0f;
960  for (uint8_t index = 7; index < 24; index++) {
961  H_VEL[index] = 0.0f;
962  }
963 
964  // calculate intermediate expressions for X axis Kalman gains
965  float R_VEL = sq(bodyOdmDataDelayed.velErr);
966  float t2 = q0*q3*2.0f;
967  float t3 = q1*q2*2.0f;
968  float t4 = t2+t3;
969  float t5 = q0*q0;
970  float t6 = q1*q1;
971  float t7 = q2*q2;
972  float t8 = q3*q3;
973  float t9 = t5+t6-t7-t8;
974  float t10 = q0*q2*2.0f;
975  float t25 = q1*q3*2.0f;
976  float t11 = t10-t25;
977  float t12 = q3*ve*2.0f;
978  float t13 = q0*vn*2.0f;
979  float t26 = q2*vd*2.0f;
980  float t14 = t12+t13-t26;
981  float t15 = q3*vd*2.0f;
982  float t16 = q2*ve*2.0f;
983  float t17 = q1*vn*2.0f;
984  float t18 = t15+t16+t17;
985  float t19 = q0*vd*2.0f;
986  float t20 = q2*vn*2.0f;
987  float t27 = q1*ve*2.0f;
988  float t21 = t19+t20-t27;
989  float t22 = q1*vd*2.0f;
990  float t23 = q0*ve*2.0f;
991  float t28 = q3*vn*2.0f;
992  float t24 = t22+t23-t28;
993  float t29 = P[0][0]*t14;
994  float t30 = P[1][1]*t18;
995  float t31 = P[4][5]*t9;
996  float t32 = P[5][5]*t4;
997  float t33 = P[0][5]*t14;
998  float t34 = P[1][5]*t18;
999  float t35 = P[3][5]*t24;
1000  float t79 = P[6][5]*t11;
1001  float t80 = P[2][5]*t21;
1002  float t36 = t31+t32+t33+t34+t35-t79-t80;
1003  float t37 = t4*t36;
1004  float t38 = P[4][6]*t9;
1005  float t39 = P[5][6]*t4;
1006  float t40 = P[0][6]*t14;
1007  float t41 = P[1][6]*t18;
1008  float t42 = P[3][6]*t24;
1009  float t81 = P[6][6]*t11;
1010  float t82 = P[2][6]*t21;
1011  float t43 = t38+t39+t40+t41+t42-t81-t82;
1012  float t44 = P[4][0]*t9;
1013  float t45 = P[5][0]*t4;
1014  float t46 = P[1][0]*t18;
1015  float t47 = P[3][0]*t24;
1016  float t84 = P[6][0]*t11;
1017  float t85 = P[2][0]*t21;
1018  float t48 = t29+t44+t45+t46+t47-t84-t85;
1019  float t49 = t14*t48;
1020  float t50 = P[4][1]*t9;
1021  float t51 = P[5][1]*t4;
1022  float t52 = P[0][1]*t14;
1023  float t53 = P[3][1]*t24;
1024  float t86 = P[6][1]*t11;
1025  float t87 = P[2][1]*t21;
1026  float t54 = t30+t50+t51+t52+t53-t86-t87;
1027  float t55 = t18*t54;
1028  float t56 = P[4][2]*t9;
1029  float t57 = P[5][2]*t4;
1030  float t58 = P[0][2]*t14;
1031  float t59 = P[1][2]*t18;
1032  float t60 = P[3][2]*t24;
1033  float t78 = P[2][2]*t21;
1034  float t88 = P[6][2]*t11;
1035  float t61 = t56+t57+t58+t59+t60-t78-t88;
1036  float t62 = P[4][3]*t9;
1037  float t63 = P[5][3]*t4;
1038  float t64 = P[0][3]*t14;
1039  float t65 = P[1][3]*t18;
1040  float t66 = P[3][3]*t24;
1041  float t90 = P[6][3]*t11;
1042  float t91 = P[2][3]*t21;
1043  float t67 = t62+t63+t64+t65+t66-t90-t91;
1044  float t68 = t24*t67;
1045  float t69 = P[4][4]*t9;
1046  float t70 = P[5][4]*t4;
1047  float t71 = P[0][4]*t14;
1048  float t72 = P[1][4]*t18;
1049  float t73 = P[3][4]*t24;
1050  float t92 = P[6][4]*t11;
1051  float t93 = P[2][4]*t21;
1052  float t74 = t69+t70+t71+t72+t73-t92-t93;
1053  float t75 = t9*t74;
1054  float t83 = t11*t43;
1055  float t89 = t21*t61;
1056  float t76 = R_VEL+t37+t49+t55+t68+t75-t83-t89;
1057  float t77;
1058 
1059  // calculate innovation variance for X axis observation and protect against a badly conditioned calculation
1060  if (t76 > R_VEL) {
1061  t77 = 1.0f/t76;
1062  faultStatus.bad_xvel = false;
1063  } else {
1064  t76 = R_VEL;
1065  t77 = 1.0f/R_VEL;
1066  faultStatus.bad_xvel = true;
1067  return;
1068  }
1069  varInnovBodyVel[0] = t77;
1070 
1071  // calculate innovation for X axis observation
1072  innovBodyVel[0] = bodyVelPred.x - bodyOdmDataDelayed.vel.x;
1073 
1074  // calculate Kalman gains for X-axis observation
1075  Kfusion[0] = t77*(t29+P[0][5]*t4+P[0][4]*t9-P[0][6]*t11+P[0][1]*t18-P[0][2]*t21+P[0][3]*t24);
1076  Kfusion[1] = t77*(t30+P[1][5]*t4+P[1][4]*t9+P[1][0]*t14-P[1][6]*t11-P[1][2]*t21+P[1][3]*t24);
1077  Kfusion[2] = t77*(-t78+P[2][5]*t4+P[2][4]*t9+P[2][0]*t14-P[2][6]*t11+P[2][1]*t18+P[2][3]*t24);
1078  Kfusion[3] = t77*(t66+P[3][5]*t4+P[3][4]*t9+P[3][0]*t14-P[3][6]*t11+P[3][1]*t18-P[3][2]*t21);
1079  Kfusion[4] = t77*(t69+P[4][5]*t4+P[4][0]*t14-P[4][6]*t11+P[4][1]*t18-P[4][2]*t21+P[4][3]*t24);
1080  Kfusion[5] = t77*(t32+P[5][4]*t9+P[5][0]*t14-P[5][6]*t11+P[5][1]*t18-P[5][2]*t21+P[5][3]*t24);
1081  Kfusion[6] = t77*(-t81+P[6][5]*t4+P[6][4]*t9+P[6][0]*t14+P[6][1]*t18-P[6][2]*t21+P[6][3]*t24);
1082  Kfusion[7] = t77*(P[7][5]*t4+P[7][4]*t9+P[7][0]*t14-P[7][6]*t11+P[7][1]*t18-P[7][2]*t21+P[7][3]*t24);
1083  Kfusion[8] = t77*(P[8][5]*t4+P[8][4]*t9+P[8][0]*t14-P[8][6]*t11+P[8][1]*t18-P[8][2]*t21+P[8][3]*t24);
1084  Kfusion[9] = t77*(P[9][5]*t4+P[9][4]*t9+P[9][0]*t14-P[9][6]*t11+P[9][1]*t18-P[9][2]*t21+P[9][3]*t24);
1085 
1086  if (!inhibitDelAngBiasStates) {
1087  Kfusion[10] = t77*(P[10][5]*t4+P[10][4]*t9+P[10][0]*t14-P[10][6]*t11+P[10][1]*t18-P[10][2]*t21+P[10][3]*t24);
1088  Kfusion[11] = t77*(P[11][5]*t4+P[11][4]*t9+P[11][0]*t14-P[11][6]*t11+P[11][1]*t18-P[11][2]*t21+P[11][3]*t24);
1089  Kfusion[12] = t77*(P[12][5]*t4+P[12][4]*t9+P[12][0]*t14-P[12][6]*t11+P[12][1]*t18-P[12][2]*t21+P[12][3]*t24);
1090  } else {
1091  // zero indexes 10 to 12 = 3*4 bytes
1092  memset(&Kfusion[10], 0, 12);
1093  }
1094 
1095  if (!inhibitDelVelBiasStates) {
1096  Kfusion[13] = t77*(P[13][5]*t4+P[13][4]*t9+P[13][0]*t14-P[13][6]*t11+P[13][1]*t18-P[13][2]*t21+P[13][3]*t24);
1097  Kfusion[14] = t77*(P[14][5]*t4+P[14][4]*t9+P[14][0]*t14-P[14][6]*t11+P[14][1]*t18-P[14][2]*t21+P[14][3]*t24);
1098  Kfusion[15] = t77*(P[15][5]*t4+P[15][4]*t9+P[15][0]*t14-P[15][6]*t11+P[15][1]*t18-P[15][2]*t21+P[15][3]*t24);
1099  } else {
1100  // zero indexes 13 to 15 = 3*4 bytes
1101  memset(&Kfusion[13], 0, 12);
1102  }
1103 
1104  if (!inhibitMagStates) {
1105  Kfusion[16] = t77*(P[16][5]*t4+P[16][4]*t9+P[16][0]*t14-P[16][6]*t11+P[16][1]*t18-P[16][2]*t21+P[16][3]*t24);
1106  Kfusion[17] = t77*(P[17][5]*t4+P[17][4]*t9+P[17][0]*t14-P[17][6]*t11+P[17][1]*t18-P[17][2]*t21+P[17][3]*t24);
1107  Kfusion[18] = t77*(P[18][5]*t4+P[18][4]*t9+P[18][0]*t14-P[18][6]*t11+P[18][1]*t18-P[18][2]*t21+P[18][3]*t24);
1108  Kfusion[19] = t77*(P[19][5]*t4+P[19][4]*t9+P[19][0]*t14-P[19][6]*t11+P[19][1]*t18-P[19][2]*t21+P[19][3]*t24);
1109  Kfusion[20] = t77*(P[20][5]*t4+P[20][4]*t9+P[20][0]*t14-P[20][6]*t11+P[20][1]*t18-P[20][2]*t21+P[20][3]*t24);
1110  Kfusion[21] = t77*(P[21][5]*t4+P[21][4]*t9+P[21][0]*t14-P[21][6]*t11+P[21][1]*t18-P[21][2]*t21+P[21][3]*t24);
1111  } else {
1112  // zero indexes 16 to 21 = 6*4 bytes
1113  memset(&Kfusion[16], 0, 24);
1114  }
1115 
1116  if (!inhibitWindStates) {
1117  Kfusion[22] = t77*(P[22][5]*t4+P[22][4]*t9+P[22][0]*t14-P[22][6]*t11+P[22][1]*t18-P[22][2]*t21+P[22][3]*t24);
1118  Kfusion[23] = t77*(P[23][5]*t4+P[23][4]*t9+P[23][0]*t14-P[23][6]*t11+P[23][1]*t18-P[23][2]*t21+P[23][3]*t24);
1119  } else {
1120  // zero indexes 22 to 23 = 2*4 bytes
1121  memset(&Kfusion[22], 0, 8);
1122  }
1123  } else if (obsIndex == 1) {
1124  // calculate Y axis observation Jacobian
1125  H_VEL[0] = q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f;
1126  H_VEL[1] = q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f;
1127  H_VEL[2] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
1128  H_VEL[3] = q2*vd*2.0f-q3*ve*2.0f-q0*vn*2.0f;
1129  H_VEL[4] = q0*q3*-2.0f+q1*q2*2.0f;
1130  H_VEL[5] = q0*q0-q1*q1+q2*q2-q3*q3;
1131  H_VEL[6] = q0*q1*2.0f+q2*q3*2.0f;
1132  for (uint8_t index = 7; index < 24; index++) {
1133  H_VEL[index] = 0.0f;
1134  }
1135 
1136  // calculate intermediate expressions for Y axis Kalman gains
1137  float R_VEL = sq(bodyOdmDataDelayed.velErr);
1138  float t2 = q0*q3*2.0f;
1139  float t9 = q1*q2*2.0f;
1140  float t3 = t2-t9;
1141  float t4 = q0*q0;
1142  float t5 = q1*q1;
1143  float t6 = q2*q2;
1144  float t7 = q3*q3;
1145  float t8 = t4-t5+t6-t7;
1146  float t10 = q0*q1*2.0f;
1147  float t11 = q2*q3*2.0f;
1148  float t12 = t10+t11;
1149  float t13 = q1*vd*2.0f;
1150  float t14 = q0*ve*2.0f;
1151  float t26 = q3*vn*2.0f;
1152  float t15 = t13+t14-t26;
1153  float t16 = q0*vd*2.0f;
1154  float t17 = q2*vn*2.0f;
1155  float t27 = q1*ve*2.0f;
1156  float t18 = t16+t17-t27;
1157  float t19 = q3*vd*2.0f;
1158  float t20 = q2*ve*2.0f;
1159  float t21 = q1*vn*2.0f;
1160  float t22 = t19+t20+t21;
1161  float t23 = q3*ve*2.0f;
1162  float t24 = q0*vn*2.0f;
1163  float t28 = q2*vd*2.0f;
1164  float t25 = t23+t24-t28;
1165  float t29 = P[0][0]*t15;
1166  float t30 = P[1][1]*t18;
1167  float t31 = P[5][4]*t8;
1168  float t32 = P[6][4]*t12;
1169  float t33 = P[0][4]*t15;
1170  float t34 = P[1][4]*t18;
1171  float t35 = P[2][4]*t22;
1172  float t78 = P[4][4]*t3;
1173  float t79 = P[3][4]*t25;
1174  float t36 = t31+t32+t33+t34+t35-t78-t79;
1175  float t37 = P[5][6]*t8;
1176  float t38 = P[6][6]*t12;
1177  float t39 = P[0][6]*t15;
1178  float t40 = P[1][6]*t18;
1179  float t41 = P[2][6]*t22;
1180  float t81 = P[4][6]*t3;
1181  float t82 = P[3][6]*t25;
1182  float t42 = t37+t38+t39+t40+t41-t81-t82;
1183  float t43 = t12*t42;
1184  float t44 = P[5][0]*t8;
1185  float t45 = P[6][0]*t12;
1186  float t46 = P[1][0]*t18;
1187  float t47 = P[2][0]*t22;
1188  float t83 = P[4][0]*t3;
1189  float t84 = P[3][0]*t25;
1190  float t48 = t29+t44+t45+t46+t47-t83-t84;
1191  float t49 = t15*t48;
1192  float t50 = P[5][1]*t8;
1193  float t51 = P[6][1]*t12;
1194  float t52 = P[0][1]*t15;
1195  float t53 = P[2][1]*t22;
1196  float t85 = P[4][1]*t3;
1197  float t86 = P[3][1]*t25;
1198  float t54 = t30+t50+t51+t52+t53-t85-t86;
1199  float t55 = t18*t54;
1200  float t56 = P[5][2]*t8;
1201  float t57 = P[6][2]*t12;
1202  float t58 = P[0][2]*t15;
1203  float t59 = P[1][2]*t18;
1204  float t60 = P[2][2]*t22;
1205  float t87 = P[4][2]*t3;
1206  float t88 = P[3][2]*t25;
1207  float t61 = t56+t57+t58+t59+t60-t87-t88;
1208  float t62 = t22*t61;
1209  float t63 = P[5][3]*t8;
1210  float t64 = P[6][3]*t12;
1211  float t65 = P[0][3]*t15;
1212  float t66 = P[1][3]*t18;
1213  float t67 = P[2][3]*t22;
1214  float t89 = P[4][3]*t3;
1215  float t90 = P[3][3]*t25;
1216  float t68 = t63+t64+t65+t66+t67-t89-t90;
1217  float t69 = P[5][5]*t8;
1218  float t70 = P[6][5]*t12;
1219  float t71 = P[0][5]*t15;
1220  float t72 = P[1][5]*t18;
1221  float t73 = P[2][5]*t22;
1222  float t92 = P[4][5]*t3;
1223  float t93 = P[3][5]*t25;
1224  float t74 = t69+t70+t71+t72+t73-t92-t93;
1225  float t75 = t8*t74;
1226  float t80 = t3*t36;
1227  float t91 = t25*t68;
1228  float t76 = R_VEL+t43+t49+t55+t62+t75-t80-t91;
1229  float t77;
1230 
1231  // calculate innovation variance for Y axis observation and protect against a badly conditioned calculation
1232  if (t76 > R_VEL) {
1233  t77 = 1.0f/t76;
1234  faultStatus.bad_yvel = false;
1235  } else {
1236  t76 = R_VEL;
1237  t77 = 1.0f/R_VEL;
1238  faultStatus.bad_yvel = true;
1239  return;
1240  }
1241  varInnovBodyVel[1] = t77;
1242 
1243  // calculate innovation for Y axis observation
1244  innovBodyVel[1] = bodyVelPred.y - bodyOdmDataDelayed.vel.y;
1245 
1246  // calculate Kalman gains for Y-axis observation
1247  Kfusion[0] = t77*(t29-P[0][4]*t3+P[0][5]*t8+P[0][6]*t12+P[0][1]*t18+P[0][2]*t22-P[0][3]*t25);
1248  Kfusion[1] = t77*(t30-P[1][4]*t3+P[1][5]*t8+P[1][0]*t15+P[1][6]*t12+P[1][2]*t22-P[1][3]*t25);
1249  Kfusion[2] = t77*(t60-P[2][4]*t3+P[2][5]*t8+P[2][0]*t15+P[2][6]*t12+P[2][1]*t18-P[2][3]*t25);
1250  Kfusion[3] = t77*(-t90-P[3][4]*t3+P[3][5]*t8+P[3][0]*t15+P[3][6]*t12+P[3][1]*t18+P[3][2]*t22);
1251  Kfusion[4] = t77*(-t78+P[4][5]*t8+P[4][0]*t15+P[4][6]*t12+P[4][1]*t18+P[4][2]*t22-P[4][3]*t25);
1252  Kfusion[5] = t77*(t69-P[5][4]*t3+P[5][0]*t15+P[5][6]*t12+P[5][1]*t18+P[5][2]*t22-P[5][3]*t25);
1253  Kfusion[6] = t77*(t38-P[6][4]*t3+P[6][5]*t8+P[6][0]*t15+P[6][1]*t18+P[6][2]*t22-P[6][3]*t25);
1254  Kfusion[7] = t77*(-P[7][4]*t3+P[7][5]*t8+P[7][0]*t15+P[7][6]*t12+P[7][1]*t18+P[7][2]*t22-P[7][3]*t25);
1255  Kfusion[8] = t77*(-P[8][4]*t3+P[8][5]*t8+P[8][0]*t15+P[8][6]*t12+P[8][1]*t18+P[8][2]*t22-P[8][3]*t25);
1256  Kfusion[9] = t77*(-P[9][4]*t3+P[9][5]*t8+P[9][0]*t15+P[9][6]*t12+P[9][1]*t18+P[9][2]*t22-P[9][3]*t25);
1257 
1258  if (!inhibitDelAngBiasStates) {
1259  Kfusion[10] = t77*(-P[10][4]*t3+P[10][5]*t8+P[10][0]*t15+P[10][6]*t12+P[10][1]*t18+P[10][2]*t22-P[10][3]*t25);
1260  Kfusion[11] = t77*(-P[11][4]*t3+P[11][5]*t8+P[11][0]*t15+P[11][6]*t12+P[11][1]*t18+P[11][2]*t22-P[11][3]*t25);
1261  Kfusion[12] = t77*(-P[12][4]*t3+P[12][5]*t8+P[12][0]*t15+P[12][6]*t12+P[12][1]*t18+P[12][2]*t22-P[12][3]*t25);
1262  } else {
1263  // zero indexes 10 to 12 = 3*4 bytes
1264  memset(&Kfusion[10], 0, 12);
1265  }
1266 
1267  if (!inhibitDelVelBiasStates) {
1268  Kfusion[13] = t77*(-P[13][4]*t3+P[13][5]*t8+P[13][0]*t15+P[13][6]*t12+P[13][1]*t18+P[13][2]*t22-P[13][3]*t25);
1269  Kfusion[14] = t77*(-P[14][4]*t3+P[14][5]*t8+P[14][0]*t15+P[14][6]*t12+P[14][1]*t18+P[14][2]*t22-P[14][3]*t25);
1270  Kfusion[15] = t77*(-P[15][4]*t3+P[15][5]*t8+P[15][0]*t15+P[15][6]*t12+P[15][1]*t18+P[15][2]*t22-P[15][3]*t25);
1271  } else {
1272  // zero indexes 13 to 15 = 3*4 bytes
1273  memset(&Kfusion[13], 0, 12);
1274  }
1275 
1276  if (!inhibitMagStates) {
1277  Kfusion[16] = t77*(-P[16][4]*t3+P[16][5]*t8+P[16][0]*t15+P[16][6]*t12+P[16][1]*t18+P[16][2]*t22-P[16][3]*t25);
1278  Kfusion[17] = t77*(-P[17][4]*t3+P[17][5]*t8+P[17][0]*t15+P[17][6]*t12+P[17][1]*t18+P[17][2]*t22-P[17][3]*t25);
1279  Kfusion[18] = t77*(-P[18][4]*t3+P[18][5]*t8+P[18][0]*t15+P[18][6]*t12+P[18][1]*t18+P[18][2]*t22-P[18][3]*t25);
1280  Kfusion[19] = t77*(-P[19][4]*t3+P[19][5]*t8+P[19][0]*t15+P[19][6]*t12+P[19][1]*t18+P[19][2]*t22-P[19][3]*t25);
1281  Kfusion[20] = t77*(-P[20][4]*t3+P[20][5]*t8+P[20][0]*t15+P[20][6]*t12+P[20][1]*t18+P[20][2]*t22-P[20][3]*t25);
1282  Kfusion[21] = t77*(-P[21][4]*t3+P[21][5]*t8+P[21][0]*t15+P[21][6]*t12+P[21][1]*t18+P[21][2]*t22-P[21][3]*t25);
1283  } else {
1284  // zero indexes 16 to 21 = 6*4 bytes
1285  memset(&Kfusion[16], 0, 24);
1286  }
1287 
1288  if (!inhibitWindStates) {
1289  Kfusion[22] = t77*(-P[22][4]*t3+P[22][5]*t8+P[22][0]*t15+P[22][6]*t12+P[22][1]*t18+P[22][2]*t22-P[22][3]*t25);
1290  Kfusion[23] = t77*(-P[23][4]*t3+P[23][5]*t8+P[23][0]*t15+P[23][6]*t12+P[23][1]*t18+P[23][2]*t22-P[23][3]*t25);
1291  } else {
1292  // zero indexes 22 to 23 = 2*4 bytes
1293  memset(&Kfusion[22], 0, 8);
1294  }
1295  } else if (obsIndex == 2) {
1296  // calculate Z axis observation Jacobian
1297  H_VEL[0] = q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f;
1298  H_VEL[1] = q1*vd*-2.0f-q0*ve*2.0f+q3*vn*2.0f;
1299  H_VEL[2] = q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f;
1300  H_VEL[3] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
1301  H_VEL[4] = q0*q2*2.0f+q1*q3*2.0f;
1302  H_VEL[5] = q0*q1*-2.0f+q2*q3*2.0f;
1303  H_VEL[6] = q0*q0-q1*q1-q2*q2+q3*q3;
1304  for (uint8_t index = 7; index < 24; index++) {
1305  H_VEL[index] = 0.0f;
1306  }
1307 
1308  // calculate intermediate expressions for Z axis Kalman gains
1309  float R_VEL = sq(bodyOdmDataDelayed.velErr);
1310  float t2 = q0*q2*2.0f;
1311  float t3 = q1*q3*2.0f;
1312  float t4 = t2+t3;
1313  float t5 = q0*q0;
1314  float t6 = q1*q1;
1315  float t7 = q2*q2;
1316  float t8 = q3*q3;
1317  float t9 = t5-t6-t7+t8;
1318  float t10 = q0*q1*2.0f;
1319  float t25 = q2*q3*2.0f;
1320  float t11 = t10-t25;
1321  float t12 = q0*vd*2.0f;
1322  float t13 = q2*vn*2.0f;
1323  float t26 = q1*ve*2.0f;
1324  float t14 = t12+t13-t26;
1325  float t15 = q1*vd*2.0f;
1326  float t16 = q0*ve*2.0f;
1327  float t27 = q3*vn*2.0f;
1328  float t17 = t15+t16-t27;
1329  float t18 = q3*ve*2.0f;
1330  float t19 = q0*vn*2.0f;
1331  float t28 = q2*vd*2.0f;
1332  float t20 = t18+t19-t28;
1333  float t21 = q3*vd*2.0f;
1334  float t22 = q2*ve*2.0f;
1335  float t23 = q1*vn*2.0f;
1336  float t24 = t21+t22+t23;
1337  float t29 = P[0][0]*t14;
1338  float t30 = P[6][4]*t9;
1339  float t31 = P[4][4]*t4;
1340  float t32 = P[0][4]*t14;
1341  float t33 = P[2][4]*t20;
1342  float t34 = P[3][4]*t24;
1343  float t78 = P[5][4]*t11;
1344  float t79 = P[1][4]*t17;
1345  float t35 = t30+t31+t32+t33+t34-t78-t79;
1346  float t36 = t4*t35;
1347  float t37 = P[6][5]*t9;
1348  float t38 = P[4][5]*t4;
1349  float t39 = P[0][5]*t14;
1350  float t40 = P[2][5]*t20;
1351  float t41 = P[3][5]*t24;
1352  float t80 = P[5][5]*t11;
1353  float t81 = P[1][5]*t17;
1354  float t42 = t37+t38+t39+t40+t41-t80-t81;
1355  float t43 = P[6][0]*t9;
1356  float t44 = P[4][0]*t4;
1357  float t45 = P[2][0]*t20;
1358  float t46 = P[3][0]*t24;
1359  float t83 = P[5][0]*t11;
1360  float t84 = P[1][0]*t17;
1361  float t47 = t29+t43+t44+t45+t46-t83-t84;
1362  float t48 = t14*t47;
1363  float t49 = P[6][1]*t9;
1364  float t50 = P[4][1]*t4;
1365  float t51 = P[0][1]*t14;
1366  float t52 = P[2][1]*t20;
1367  float t53 = P[3][1]*t24;
1368  float t85 = P[5][1]*t11;
1369  float t86 = P[1][1]*t17;
1370  float t54 = t49+t50+t51+t52+t53-t85-t86;
1371  float t55 = P[6][2]*t9;
1372  float t56 = P[4][2]*t4;
1373  float t57 = P[0][2]*t14;
1374  float t58 = P[2][2]*t20;
1375  float t59 = P[3][2]*t24;
1376  float t88 = P[5][2]*t11;
1377  float t89 = P[1][2]*t17;
1378  float t60 = t55+t56+t57+t58+t59-t88-t89;
1379  float t61 = t20*t60;
1380  float t62 = P[6][3]*t9;
1381  float t63 = P[4][3]*t4;
1382  float t64 = P[0][3]*t14;
1383  float t65 = P[2][3]*t20;
1384  float t66 = P[3][3]*t24;
1385  float t90 = P[5][3]*t11;
1386  float t91 = P[1][3]*t17;
1387  float t67 = t62+t63+t64+t65+t66-t90-t91;
1388  float t68 = t24*t67;
1389  float t69 = P[6][6]*t9;
1390  float t70 = P[4][6]*t4;
1391  float t71 = P[0][6]*t14;
1392  float t72 = P[2][6]*t20;
1393  float t73 = P[3][6]*t24;
1394  float t92 = P[5][6]*t11;
1395  float t93 = P[1][6]*t17;
1396  float t74 = t69+t70+t71+t72+t73-t92-t93;
1397  float t75 = t9*t74;
1398  float t82 = t11*t42;
1399  float t87 = t17*t54;
1400  float t76 = R_VEL+t36+t48+t61+t68+t75-t82-t87;
1401  float t77;
1402 
1403  // calculate innovation variance for Z axis observation and protect against a badly conditioned calculation
1404  if (t76 > R_VEL) {
1405  t77 = 1.0f/t76;
1406  faultStatus.bad_zvel = false;
1407  } else {
1408  t76 = R_VEL;
1409  t77 = 1.0f/R_VEL;
1410  faultStatus.bad_zvel = true;
1411  return;
1412  }
1413  varInnovBodyVel[2] = t77;
1414 
1415  // calculate innovation for Z axis observation
1416  innovBodyVel[2] = bodyVelPred.z - bodyOdmDataDelayed.vel.z;
1417 
1418  // calculate Kalman gains for X-axis observation
1419  Kfusion[0] = t77*(t29+P[0][4]*t4+P[0][6]*t9-P[0][5]*t11-P[0][1]*t17+P[0][2]*t20+P[0][3]*t24);
1420  Kfusion[1] = t77*(P[1][4]*t4+P[1][0]*t14+P[1][6]*t9-P[1][5]*t11-P[1][1]*t17+P[1][2]*t20+P[1][3]*t24);
1421  Kfusion[2] = t77*(t58+P[2][4]*t4+P[2][0]*t14+P[2][6]*t9-P[2][5]*t11-P[2][1]*t17+P[2][3]*t24);
1422  Kfusion[3] = t77*(t66+P[3][4]*t4+P[3][0]*t14+P[3][6]*t9-P[3][5]*t11-P[3][1]*t17+P[3][2]*t20);
1423  Kfusion[4] = t77*(t31+P[4][0]*t14+P[4][6]*t9-P[4][5]*t11-P[4][1]*t17+P[4][2]*t20+P[4][3]*t24);
1424  Kfusion[5] = t77*(-t80+P[5][4]*t4+P[5][0]*t14+P[5][6]*t9-P[5][1]*t17+P[5][2]*t20+P[5][3]*t24);
1425  Kfusion[6] = t77*(t69+P[6][4]*t4+P[6][0]*t14-P[6][5]*t11-P[6][1]*t17+P[6][2]*t20+P[6][3]*t24);
1426  Kfusion[7] = t77*(P[7][4]*t4+P[7][0]*t14+P[7][6]*t9-P[7][5]*t11-P[7][1]*t17+P[7][2]*t20+P[7][3]*t24);
1427  Kfusion[8] = t77*(P[8][4]*t4+P[8][0]*t14+P[8][6]*t9-P[8][5]*t11-P[8][1]*t17+P[8][2]*t20+P[8][3]*t24);
1428  Kfusion[9] = t77*(P[9][4]*t4+P[9][0]*t14+P[9][6]*t9-P[9][5]*t11-P[9][1]*t17+P[9][2]*t20+P[9][3]*t24);
1429 
1430  if (!inhibitDelAngBiasStates) {
1431  Kfusion[10] = t77*(P[10][4]*t4+P[10][0]*t14+P[10][6]*t9-P[10][5]*t11-P[10][1]*t17+P[10][2]*t20+P[10][3]*t24);
1432  Kfusion[11] = t77*(P[11][4]*t4+P[11][0]*t14+P[11][6]*t9-P[11][5]*t11-P[11][1]*t17+P[11][2]*t20+P[11][3]*t24);
1433  Kfusion[12] = t77*(P[12][4]*t4+P[12][0]*t14+P[12][6]*t9-P[12][5]*t11-P[12][1]*t17+P[12][2]*t20+P[12][3]*t24);
1434  } else {
1435  // zero indexes 10 to 12 = 3*4 bytes
1436  memset(&Kfusion[10], 0, 12);
1437 
1438  }
1439 
1440  if (!inhibitDelVelBiasStates) {
1441  Kfusion[13] = t77*(P[13][4]*t4+P[13][0]*t14+P[13][6]*t9-P[13][5]*t11-P[13][1]*t17+P[13][2]*t20+P[13][3]*t24);
1442  Kfusion[14] = t77*(P[14][4]*t4+P[14][0]*t14+P[14][6]*t9-P[14][5]*t11-P[14][1]*t17+P[14][2]*t20+P[14][3]*t24);
1443  Kfusion[15] = t77*(P[15][4]*t4+P[15][0]*t14+P[15][6]*t9-P[15][5]*t11-P[15][1]*t17+P[15][2]*t20+P[15][3]*t24);
1444  } else {
1445  // zero indexes 13 to 15 = 3*4 bytes
1446  memset(&Kfusion[13], 0, 12);
1447  }
1448 
1449  if (!inhibitMagStates) {
1450  Kfusion[16] = t77*(P[16][4]*t4+P[16][0]*t14+P[16][6]*t9-P[16][5]*t11-P[16][1]*t17+P[16][2]*t20+P[16][3]*t24);
1451  Kfusion[17] = t77*(P[17][4]*t4+P[17][0]*t14+P[17][6]*t9-P[17][5]*t11-P[17][1]*t17+P[17][2]*t20+P[17][3]*t24);
1452  Kfusion[18] = t77*(P[18][4]*t4+P[18][0]*t14+P[18][6]*t9-P[18][5]*t11-P[18][1]*t17+P[18][2]*t20+P[18][3]*t24);
1453  Kfusion[19] = t77*(P[19][4]*t4+P[19][0]*t14+P[19][6]*t9-P[19][5]*t11-P[19][1]*t17+P[19][2]*t20+P[19][3]*t24);
1454  Kfusion[20] = t77*(P[20][4]*t4+P[20][0]*t14+P[20][6]*t9-P[20][5]*t11-P[20][1]*t17+P[20][2]*t20+P[20][3]*t24);
1455  Kfusion[21] = t77*(P[21][4]*t4+P[21][0]*t14+P[21][6]*t9-P[21][5]*t11-P[21][1]*t17+P[21][2]*t20+P[21][3]*t24);
1456  } else {
1457  // zero indexes 16 to 21 = 6*4 bytes
1458  memset(&Kfusion[16], 0, 24);
1459  }
1460 
1461  if (!inhibitWindStates) {
1462  Kfusion[22] = t77*(P[22][4]*t4+P[22][0]*t14+P[22][6]*t9-P[22][5]*t11-P[22][1]*t17+P[22][2]*t20+P[22][3]*t24);
1463  Kfusion[23] = t77*(P[23][4]*t4+P[23][0]*t14+P[23][6]*t9-P[23][5]*t11-P[23][1]*t17+P[23][2]*t20+P[23][3]*t24);
1464  } else {
1465  // zero indexes 22 to 23 = 2*4 bytes
1466  memset(&Kfusion[22], 0, 8);
1467  }
1468  } else {
1469  return;
1470  }
1471 
1472  // calculate the innovation consistency test ratio
1473  // TODO add tuning parameter for gate
1475 
1476  // Check the innovation for consistency and don't fuse if out of bounds
1477  // TODO also apply angular velocity magnitude check
1478  if ((bodyVelTestRatio[obsIndex]) < 1.0f) {
1479  // record the last time observations were accepted for fusion
1481  // notify first time only
1482  if (!bodyVelFusionActive) {
1483  bodyVelFusionActive = true;
1484  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u fusing odometry",(unsigned)imu_index);
1485  }
1486  // correct the covariance P = (I - K*H)*P
1487  // take advantage of the empty columns in KH to reduce the
1488  // number of operations
1489  for (unsigned i = 0; i<=stateIndexLim; i++) {
1490  for (unsigned j = 0; j<=6; j++) {
1491  KH[i][j] = Kfusion[i] * H_VEL[j];
1492  }
1493  for (unsigned j = 7; j<=stateIndexLim; j++) {
1494  KH[i][j] = 0.0f;
1495  }
1496  }
1497  for (unsigned j = 0; j<=stateIndexLim; j++) {
1498  for (unsigned i = 0; i<=stateIndexLim; i++) {
1499  ftype res = 0;
1500  res += KH[i][0] * P[0][j];
1501  res += KH[i][1] * P[1][j];
1502  res += KH[i][2] * P[2][j];
1503  res += KH[i][3] * P[3][j];
1504  res += KH[i][4] * P[4][j];
1505  res += KH[i][5] * P[5][j];
1506  res += KH[i][6] * P[6][j];
1507  KHP[i][j] = res;
1508  }
1509  }
1510 
1511  // Check that we are not going to drive any variances negative and skip the update if so
1512  bool healthyFusion = true;
1513  for (uint8_t i= 0; i<=stateIndexLim; i++) {
1514  if (KHP[i][i] > P[i][i]) {
1515  healthyFusion = false;
1516  }
1517  }
1518 
1519  if (healthyFusion) {
1520  // update the covariance matrix
1521  for (uint8_t i= 0; i<=stateIndexLim; i++) {
1522  for (uint8_t j= 0; j<=stateIndexLim; j++) {
1523  P[i][j] = P[i][j] - KHP[i][j];
1524  }
1525  }
1526 
1527  // force the covariance matrix to be symmetrical and limit the variances to prevent ill-condiioning.
1528  ForceSymmetry();
1530 
1531  // correct the state vector
1532  for (uint8_t j= 0; j<=stateIndexLim; j++) {
1534  }
1536 
1537  } else {
1538  // record bad axis
1539  if (obsIndex == 0) {
1540  faultStatus.bad_xvel = true;
1541  } else if (obsIndex == 1) {
1542  faultStatus.bad_yvel = true;
1543  } else if (obsIndex == 2) {
1544  faultStatus.bad_zvel = true;
1545  }
1546 
1547  }
1548  }
1549  }
1550 }
1551 
1552 // select fusion of body odometry measurements
1554 {
1555  // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
1556  // If so, don't fuse measurements on this time step to reduce frame over-runs
1557  // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
1558  if (magFusePerformed && (dtIMUavg < 0.005f) && !bodyVelFusionDelayed) {
1559  bodyVelFusionDelayed = true;
1560  return;
1561  } else {
1562  bodyVelFusionDelayed = false;
1563  }
1564 
1565  // Check for data at the fusion time horizon
1567 
1568  // start performance timer
1570 
1571  usingWheelSensors = false;
1572 
1573  // Fuse data into the main filter
1574  FuseBodyVel();
1575 
1576  // stop the performance timer
1578 
1580 
1581  // check if the delta time is too small to calculate a velocity
1583 
1584  // get the forward velocity
1586 
1587  // get the unit vector from the projection of the X axis onto the horizontal
1588  Vector3f unitVec;
1589  unitVec.x = prevTnb.a.x;
1590  unitVec.y = prevTnb.a.y;
1591  unitVec.z = 0.0f;
1592  unitVec.normalize();
1593 
1594  // multiply by forward speed to get velocity vector measured by wheel encoders
1595  Vector3f velNED = unitVec * fwdSpd;
1596 
1597  // This is a hack to enable use of the existing body frame velocity fusion method
1598  // TODO write a dedicated observation model for wheel encoders
1599  usingWheelSensors = true;
1600  bodyOdmDataDelayed.vel = prevTnb * velNED;
1603 
1604  // Fuse data into the main filter
1605  FuseBodyVel();
1606 
1607  }
1608 
1609  }
1610 }
1611 
1612 #endif // HAL_CPU_CLASS
t70
Definition: calcH_MAG.c:68
t42
Definition: calcH_MAG.c:41
t2
Definition: calcH_MAG.c:1
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
AP_Int8 _gpsGlitchRadiusMax
Definition: AP_NavEKF3.h:391
Vector24 statesArray
t50
Definition: calcH_MAG.c:48
#define EKF_TARGET_DT
AP_RangeFinder_Backend * get_backend(uint8_t id) const
Vector3 bodyVelTestRatio
uint8_t activeHgtSource
t33
Definition: calcH_MAG.c:34
gps_elements gpsDataDelayed
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
t75
Definition: calcP.c:77
AP_Int8 _originHgtMode
Definition: AP_NavEKF3.h:415
t85
Definition: calcP.c:88
t80
Definition: calcP.c:82
AP_Int16 _hgtInnovGate
Definition: AP_NavEKF3.h:387
uint32_t lastPosPassTime_ms
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF3.h:384
t73
Definition: calcH_MAG.c:72
AP_Float _wencOdmVelErr
Definition: AP_NavEKF3.h:418
t37
Definition: calcH_MAG.c: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
baro_elements baroDataDelayed
t41
Definition: calcH_MAG.c:23
void update_calibration(void)
Definition: AP_Baro.cpp:246
AP_Int16 _gpsVelInnovGate
Definition: AP_NavEKF3.h:385
bool posVelFusionDelayed
obs_ring_buffer_t< vel_odm_elements > storedBodyOdm
t26
Definition: calcH_MAG.c:27
t81
Definition: calcP.c:76
imu_elements imuDataDelayed
Interface definition for the various Ground Control System.
Vector28 Kfusion
t71
Definition: calcH_MAG.c:70
AP_Float _baroAltNoise
Definition: AP_NavEKF3.h:372
t16
Definition: calcH_MAG.c:15
gps_elements gpsDataNew
AP_Float _terrGradMax
Definition: AP_NavEKF3.h:408
t24
Definition: calcH_MAG.c:24
t34
Definition: calcH_MAG.c:69
vel_odm_elements bodyOdmDataDelayed
t28
Definition: calcH_MAG.c:29
imu_ring_buffer_t< output_elements > storedOutput
const RangeFinder & _rng
Definition: AP_NavEKF3.h:362
t82
Definition: calcP.c:83
AP_Float _gpsHorizPosNoise
Definition: AP_NavEKF3.h:371
AP_HAL::Util * util
Definition: HAL.h:115
AP_Float _noaidHorizNoise
Definition: AP_NavEKF3.h:402
uint32_t lastVelPassTime_ms
t35
Definition: calcH_MAG.c:35
uint32_t lastPosReset_ms
GCS & gcs()
t88
Definition: calcP.c:89
uint32_t lastPosResetD_ms
#define HGT_SOURCE_RNG
t61
Definition: calcH_MAG.c:59
t92
Definition: calcP.c:95
Vector3f accelPosOffset
Vector6 varInnovVelPos
t31
Definition: calcH_MAG.c:26
AidingMode PV_AidingMode
struct NavEKF3_core::@153 faultStatus
t36
Definition: calcH_MAG.c:36
uint32_t lastRngBcnPassTime_ms
const Vector3f & get_pos_offset() const
t21
Definition: calcH_MAG.c:20
t60
Definition: calcH_MAG.c:58
wheel_odm_elements wheelOdmDataDelayed
t54
Definition: calcH_MAG.c:52
AP_Int8 _altSource
Definition: AP_NavEKF3.h:397
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
const uint16_t hgtAvg_ms
Definition: AP_NavEKF3.h:436
range_elements rangeDataDelayed
struct NavEKF3_core::state_elements & stateStruct
bool inhibitDelAngBiasStates
t13
Definition: calcH_MAG.c:12
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
Vector3 innovBodyVel
t27
Definition: calcH_MAG.c:28
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
t74
Definition: calcP.c:75
t39
Definition: calcH_MAG.c:39
T y
Definition: vector2.h:37
t91
Definition: calcP.c:94
bool inhibitGpsVertVelUse
Definition: AP_NavEKF3.h:486
output_elements outputDataNew
t46
Definition: calcH_MAG.c:33
t67
Definition: calcH_MAG.c:65
const Vector3f & get_antenna_offset(uint8_t instance) const
Definition: AP_GPS.cpp:1137
t12
Definition: calcH_MAG.c:11
Vector2f lastKnownPositionNE
t87
Definition: calcP.c:72
uint32_t lastHgtPassTime_ms
t90
Definition: calcP.c:91
float receiverPosCov[3][3]
#define f(i)
const uint16_t hgtRetryTimeMode0_ms
Definition: AP_NavEKF3.h:430
t45
Definition: calcH_MAG.c:44
uint32_t lastTimeGpsReceived_ms
T y
Definition: vector3.h:67
AP_Int16 _gpsPosInnovGate
Definition: AP_NavEKF3.h:386
obs_ring_buffer_t< gps_elements > storedGPS
Vector3< T > c
Definition: matrix3.h:48
t7
Definition: calcH_MAG.c:6
resetDataSource velResetSource
t64
Definition: calcH_MAG.c:62
const uint16_t hgtRetryTimeMode12_ms
Definition: AP_NavEKF3.h:431
uint16_t hgtRetryTime_ms
t65
Definition: calcH_MAG.c:63
t56
Definition: calcH_MAG.c:54
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
t72
Definition: calcH_MAG.c:71
t66
Definition: calcH_MAG.c:64
t40
Definition: calcH_MAG.c:40
obs_ring_buffer_t< range_elements > storedRange
T z
Definition: vector3.h:67
Vector2f velResetNE
uint8_t stateIndexLim
const float gpsPosVarAccScale
Definition: AP_NavEKF3.h:424
t76
Definition: calcP.c:78
int16_t max_distance_cm_orient(enum Rotation orientation) const
t43
Definition: calcH_MAG.c:42
t38
Definition: calcH_MAG.c:38
t79
Definition: calcP.c:81
Matrix3f prevTnb
resetDataSource posResetSource
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define HGT_SOURCE_BCN
AP_HAL::Util::perf_counter_t _perf_FuseBodyOdom
void normalize()
Definition: vector3.h:176
t48
Definition: calcH_MAG.c:46
t59
Definition: calcH_MAG.c:57
#define HGT_SOURCE_BARO
t14
Definition: calcH_MAG.c:13
AP_Float _rngNoise
Definition: AP_NavEKF3.h:398
uint8_t last_gps_idx
t77
Definition: calcP.c:79
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
bool inhibitDelVelBiasStates
output_elements outputDataDelayed
struct nav_filter_status::@138 flags
t23
Definition: calcH_MAG.c:22
t89
Definition: calcP.c:90
t68
Definition: calcH_MAG.c:66
#define HGT_SOURCE_GPS
t47
Definition: calcH_MAG.c:45
t15
Definition: calcH_MAG.c:14
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
void normalize()
Definition: quaternion.cpp:297
t3
Definition: calcH_MAG.c:2
ftype Vector6[6]
t49
Definition: calcH_MAG.c:47
t8
Definition: calcH_MAG.c:7
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
t5
Definition: calcH_MAG.c:4
t93
Definition: calcP.c:97
Vector6 innovVelPos
const float gndEffectBaroScaler
Definition: AP_NavEKF3.h:445
t4
Definition: calcH_MAG.c:3
t69
Definition: calcH_MAG.c:67
obs_ring_buffer_t< wheel_odm_elements > storedWheelOdm
Vector2f posResetNE
t25
Definition: calcH_MAG.c:25
t84
Definition: calcP.c:87
uint32_t rngValidMeaTime_ms
t29
Definition: calcH_MAG.c:30
t18
Definition: calcH_MAG.c:16
uint32_t rngBcnLast3DmeasTime_ms
float sq(const T val)
Definition: AP_Math.h:170
t6
Definition: calcH_MAG.c:5
bool is_zero(void) const
Definition: vector3.h:159
t11
Definition: calcH_MAG.c:10
t32
Definition: calcH_MAG.c:32
t58
Definition: calcH_MAG.c:56
AP_Float _useRngSwSpd
Definition: AP_NavEKF3.h:412
ftype Vector24[24]
uint32_t lastVelReset_ms
t19
Definition: calcH_MAG.c:18
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
t10
Definition: calcH_MAG.c:9
t20
Definition: calcH_MAG.c:19
t17
Definition: calcH_MAG.c:17
t9
Definition: calcH_MAG.c:8
AP_Float _gpsVertVelNoise
Definition: AP_NavEKF3.h:370
AP_Baro & baro()
Definition: AP_Baro.cpp:737
float hgtInnovFiltState
t30
Definition: calcH_MAG.c:31
NavEKF3 * frontend
t44
Definition: calcH_MAG.c:43
nav_filter_status filterStatus
t51
Definition: calcH_MAG.c:49
Vector3< T > a
Definition: matrix3.h:48
obs_ring_buffer_t< baro_elements > storedBaro
t63
Definition: calcH_MAG.c:61
t22
Definition: calcH_MAG.c:21
t53
Definition: calcH_MAG.c:51
uint32_t imuSampleTime_ms
t78
Definition: calcP.c:80
t52
Definition: calcH_MAG.c:50
t83
Definition: calcP.c:84
Vector3 varInnovBodyVel
const float gpsDVelVarAccScale
Definition: AP_NavEKF3.h:423
uint32_t prevBodyVelFuseTime_ms
t86
Definition: calcP.c:71
void zero()
Definition: vector3.h:182
t55
Definition: calcH_MAG.c:53
t57
Definition: calcH_MAG.c:55
AP_Int8 _useRngSwHgt
Definition: AP_NavEKF3.h:407
const float gpsNEVelVarAccScale
Definition: AP_NavEKF3.h:422
T x
Definition: vector3.h:67
t62
Definition: calcH_MAG.c:60
uint8_t imu_buffer_length
AP_Float _gpsHorizVelNoise
Definition: AP_NavEKF3.h:369
Vector3f receiverPos