APM:Libraries
AP_NavEKF2_core.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
4 
5 #include "AP_NavEKF2.h"
6 #include "AP_NavEKF2_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 
10 #include <stdio.h>
11 
12 extern const AP_HAL::HAL& hal;
13 
14 #define earthRate 0.000072921f // earth rotation rate (rad/sec)
15 
16 // when the wind estimation first starts with no airspeed sensor,
17 // assume 3m/s to start
18 #define STARTUP_WIND_SPEED 3.0f
19 
20 // initial imu bias uncertainty (deg/sec)
21 #define INIT_ACCEL_BIAS_UNCERTAINTY 0.5f
22 
23 // maximum allowed gyro bias (rad/sec)
24 #define GYRO_BIAS_LIMIT 0.5f
25 
26 // constructor
28  stateStruct(*reinterpret_cast<struct state_elements *>(&statesArray)),
29 
30  _perf_UpdateFilter(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_UpdateFilter")),
31  _perf_CovariancePrediction(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_CovariancePrediction")),
32  _perf_FuseVelPosNED(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseVelPosNED")),
33  _perf_FuseMagnetometer(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseMagnetometer")),
34  _perf_FuseAirspeed(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseAirspeed")),
35  _perf_FuseSideslip(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseSideslip")),
36  _perf_TerrainOffset(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_TerrainOffset")),
37  _perf_FuseOptFlow(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseOptFlow"))
38 {
39  _perf_test[0] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test0");
40  _perf_test[1] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test1");
41  _perf_test[2] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test2");
42  _perf_test[3] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test3");
43  _perf_test[4] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test4");
44  _perf_test[5] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test5");
45  _perf_test[6] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test6");
46  _perf_test[7] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test7");
47  _perf_test[8] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test8");
48  _perf_test[9] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test9");
49 }
50 
51 // setup this core backend
52 bool NavEKF2_core::setup_core(NavEKF2 *_frontend, uint8_t _imu_index, uint8_t _core_index)
53 {
54  frontend = _frontend;
55  imu_index = _imu_index;
56  core_index = _core_index;
57  _ahrs = frontend->_ahrs;
58 
59  /*
60  the imu_buffer_length needs to cope with a 260ms delay at a
61  maximum fusion rate of 100Hz. Non-imu data coming in at faster
62  than 100Hz is downsampled. For 50Hz main loop rate we need a
63  shorter buffer.
64  */
65  if (AP::ins().get_sample_rate() < 100) {
66  imu_buffer_length = 13;
67  } else {
68  // maximum 260 msec delay at 100 Hz fusion rate
69  imu_buffer_length = 26;
70  }
71  if(!storedGPS.init(OBS_BUFFER_LENGTH)) {
72  return false;
73  }
74  if(!storedMag.init(OBS_BUFFER_LENGTH)) {
75  return false;
76  }
77  if(!storedBaro.init(OBS_BUFFER_LENGTH)) {
78  return false;
79  }
80  if(!storedTAS.init(OBS_BUFFER_LENGTH)) {
81  return false;
82  }
83  if(!storedOF.init(OBS_BUFFER_LENGTH)) {
84  return false;
85  }
86  // Note: the use of dual range finders potentially doubles the amount of to be stored
87  if(!storedRange.init(2*OBS_BUFFER_LENGTH)) {
88  return false;
89  }
90  // Note: range beacon data is read one beacon at a time and can arrive at a high rate
92  return false;
93  }
94  if(!storedExtNav.init(OBS_BUFFER_LENGTH)) {
95  return false;
96  }
97  if(!storedIMU.init(imu_buffer_length)) {
98  return false;
99  }
100  if(!storedOutput.init(imu_buffer_length)) {
101  return false;
102  }
103 
104  return true;
105 }
106 
107 
108 /********************************************************
109 * INIT FUNCTIONS *
110 ********************************************************/
111 
112 // Use a function call rather than a constructor to initialise variables because it enables the filter to be re-started in flight if necessary.
114 {
115  // calculate the nominal filter update rate
116  const AP_InertialSensor &ins = AP::ins();
117  localFilterTimeStep_ms = (uint8_t)(1000*ins.get_loop_delta_t());
119 
120  // initialise time stamps
125  lastMagUpdate_us = 0;
127  lastVelPassTime_ms = 0;
128  lastPosPassTime_ms = 0;
129  lastHgtPassTime_ms = 0;
130  lastTasPassTime_ms = 0;
138  flowMeaTime_ms = 0;
140  gndHgtValidTime_ms = 0;
142  lastGpsVelFail_ms = 0;
144  timeTasReceived_ms = 0;
147  lastPosReset_ms = 0;
148  lastVelReset_ms = 0;
149  lastPosResetD_ms = 0;
150  lastRngMeasTime_ms = 0;
152 
153  // initialise other variables
154  gpsNoiseScaler = 1.0f;
155  hgtTimeout = true;
156  magTimeout = false;
157  allMagSensorsFailed = false;
158  tasTimeout = true;
159  badMagYaw = false;
160  badIMUdata = false;
161  finalInflightYawInit = false;
162  finalInflightMagInit = false;
163  dtIMUavg = 0.0025f;
165  dt = 0;
168  prevTnb.zero();
169  memset(&P[0][0], 0, sizeof(P));
170  memset(&nextP[0][0], 0, sizeof(nextP));
171  memset(&processNoise[0], 0, sizeof(processNoise));
172  flowDataValid = false;
173  rangeDataToFuse = false;
174  fuseOptFlowData = false;
175  Popt = 0.0f;
176  terrainState = 0.0f;
179  inhibitGndState = false;
180  flowGyroBias.x = 0;
181  flowGyroBias.y = 0;
182  heldVelNE.zero();
185  posTimeout = true;
186  velTimeout = true;
187  memset(&faultStatus, 0, sizeof(faultStatus));
188  hgtRate = 0.0f;
189  mag_state.q0 = 1;
190  mag_state.DCM.identity();
191  onGround = true;
192  prevOnGround = true;
193  inFlight = false;
194  prevInFlight = false;
195  manoeuvring = false;
196  inhibitWindStates = true;
197  inhibitMagStates = true;
198  gndOffsetValid = false;
199  validOrigin = false;
201  expectGndEffectTakeoff = false;
203  expectGndEffectTouchdown = false;
204  gpsSpdAccuracy = 0.0f;
205  gpsPosAccuracy = 0.0f;
206  gpsHgtAccuracy = 0.0f;
207  baroHgtOffset = 0.0f;
208  yawResetAngle = 0.0f;
209  lastYawReset_ms = 0;
210  tiltErrFilt = 1.0f;
211  tiltAlignComplete = false;
212  yawAlignComplete = false;
213  stateIndexLim = 23;
214  baroStoreIndex = 0;
215  rangeStoreIndex = 0;
216  magStoreIndex = 0;
217  gpsStoreIndex = 0;
218  tasStoreIndex = 0;
219  ofStoreIndex = 0;
223  gpsGoodToAlign = false;
224  gpsNotAvailable = true;
225  motorsArmed = false;
226  prevMotorsArmed = false;
228  lastInnovation = 0;
229  memset(&gpsCheckStatus, 0, sizeof(gpsCheckStatus));
230  gpsSpdAccPass = false;
231  ekfInnovationsPass = false;
232  sAccFilterState1 = 0.0f;
233  sAccFilterState2 = 0.0f;
237  gpsAccuracyGood = false;
238  memset(&gpsloc_prev, 0, sizeof(gpsloc_prev));
239  gpsDriftNE = 0.0f;
240  gpsVertVelFilt = 0.0f;
241  gpsHorizVelFilt = 0.0f;
242  memset(&statesArray, 0, sizeof(statesArray));
243  posDownDerivative = 0.0f;
244  posDown = 0.0f;
245  posVelFusionDelayed = false;
246  optFlowFusionDelayed = false;
247  airSpdFusionDelayed = false;
248  sideSlipFusionDelayed = false;
249  posResetNE.zero();
250  velResetNE.zero();
251  posResetD = 0.0f;
252  hgtInnovFiltState = 0.0f;
253  if (_ahrs->get_compass()) {
255  }
260  runUpdates = false;
261  framesSincePredict = 0;
262  lastMagOffsetsValid = false;
263  magStateResetRequest = false;
264  magStateInitComplete = false;
265  magYawResetRequest = false;
266  gpsYawResetRequest = false;
268  yawInnovAtLastMagReset = 0.0f;
270  magFieldLearned = false;
271  delAngBiasLearned = false;
272  memset(&filterStatus, 0, sizeof(filterStatus));
273  gpsInhibit = false;
274  activeHgtSource = 0;
275  memset(&rngMeasIndex, 0, sizeof(rngMeasIndex));
276  memset(&storedRngMeasTime_ms, 0, sizeof(storedRngMeasTime_ms));
277  memset(&storedRngMeas, 0, sizeof(storedRngMeas));
278  terrainHgtStable = true;
279  ekfOriginHgtVar = 0.0f;
280  ekfGpsRefHgt = 0.0;
281  velOffsetNED.zero();
282  posOffsetNED.zero();
283  memset(&velPosObs, 0, sizeof(velPosObs));
284 
285  // range beacon fusion variables
286  memset(&rngBcnDataNew, 0, sizeof(rngBcnDataNew));
287  memset(&rngBcnDataDelayed, 0, sizeof(rngBcnDataDelayed));
288  rngBcnStoreIndex = 0;
290  rngBcnTestRatio = 0.0f;
291  rngBcnHealth = false;
292  rngBcnTimeout = true;
293  varInnovRngBcn = 0.0f;
294  innovRngBcn = 0.0f;
295  memset(&lastTimeRngBcn_ms, 0, sizeof(lastTimeRngBcn_ms));
296  rngBcnDataToFuse = false;
298  beaconVehiclePosErr = 1.0f;
300  rngBcnGoodToAlign = false;
301  lastRngBcnChecked = 0;
302  receiverPos.zero();
303  memset(&receiverPosCov, 0, sizeof(receiverPosCov));
304  rngBcnAlignmentStarted = false;
305  rngBcnAlignmentCompleted = false;
306  lastBeaconIndex = 0;
307  rngBcnPosSum.zero();
308  numBcnMeas = 0;
309  rngSum = 0.0f;
310  N_beacons = 0;
311  maxBcnPosD = 0.0f;
312  minBcnPosD = 0.0f;
313  bcnPosOffset = 0.0f;
314  bcnPosOffsetMax = 0.0f;
315  bcnPosOffsetMaxVar = 0.0f;
316  OffsetMaxInnovFilt = 0.0f;
317  bcnPosOffsetMin = 0.0f;
318  bcnPosOffsetMinVar = 0.0f;
319  OffsetMinInnovFilt = 0.0f;
321  memset(&rngBcnFusionReport, 0, sizeof(rngBcnFusionReport));
322  last_gps_idx = 0;
323 
324  // external nav data fusion
325  memset(&extNavDataNew, 0, sizeof(extNavDataNew));
326  memset(&extNavDataDelayed, 0, sizeof(extNavDataDelayed));
327  extNavDataToFuse = false;
328  extNavMeasTime_ms = 0;
330  extNavUsedForYaw = false;
331  extNavUsedForPos = false;
332  extNavYawResetRequest = false;
333 
334  // zero data buffers
335  storedIMU.reset();
336  storedGPS.reset();
337  storedMag.reset();
338  storedBaro.reset();
339  storedTAS.reset();
340  storedRange.reset();
341  storedOutput.reset();
342  storedRangeBeacon.reset();
343  storedExtNav.reset();
344 }
345 
346 // Initialise the states from accelerometer and magnetometer data (if present)
347 // This method can only be used when the vehicle is static
349 {
350  // If we are a plane and don't have GPS lock then don't initialise
351  if (assume_zero_sideslip() && AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
353  sizeof(prearm_fail_string),
354  "EKF2 init failure: No GPS lock");
355  statesInitialised = false;
356  return false;
357  }
358 
359  if (statesInitialised) {
360  // we are initialised, but we don't return true until the IMU
361  // buffer has been filled. This prevents a timing
362  // vulnerability with a pause in IMU data during filter startup
363  readIMUData();
364  readMagData();
365  readGpsData();
366  readBaroData();
367  return storedIMU.is_filled();
368  }
369 
370  // set re-used variables to zero
372 
373  const AP_InertialSensor &ins = AP::ins();
374 
375  // Initialise IMU data
376  dtIMUavg = ins.get_loop_delta_t();
377  readIMUData();
378  storedIMU.reset_history(imuDataNew);
380 
381  // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
382  Vector3f initAccVec;
383 
384  // TODO we should average accel readings over several cycles
385  initAccVec = ins.get_accel(imu_index);
386 
387  // read the magnetometer data
388  readMagData();
389 
390  // normalise the acceleration vector
391  float pitch=0, roll=0;
392  if (initAccVec.length() > 0.001f) {
393  initAccVec.normalize();
394 
395  // calculate initial pitch angle
396  pitch = asinf(initAccVec.x);
397 
398  // calculate initial roll angle
399  roll = atan2f(-initAccVec.y , -initAccVec.z);
400  }
401 
402  // calculate initial roll and pitch orientation
403  stateStruct.quat.from_euler(roll, pitch, 0.0f);
404 
405  // initialise dynamic states
409 
410  // initialise static process model states
412  stateStruct.gyro_scale.x = 1.0f;
413  stateStruct.gyro_scale.y = 1.0f;
414  stateStruct.gyro_scale.z = 1.0f;
415  stateStruct.accel_zbias = 0.0f;
419 
420  // read the GPS and set the position and velocity states
421  readGpsData();
422  ResetVelocity();
423  ResetPosition();
424 
425  // read the barometer and set the height state
426  readBaroData();
427  ResetHeight();
428 
429  // define Earth rotation vector in the NED navigation frame
431 
432  // initialise the covariance matrix
433  CovarianceInit();
434 
435  // reset output states
437 
438  // set to true now that states have be initialised
439  statesInitialised = true;
440 
441  // we initially return false to wait for the IMU buffer to fill
442  return false;
443 }
444 
445 // initialise the covariance matrix
447 {
448  // zero the matrix
449  memset(P, 0, sizeof(P));
450 
451  // attitude error
452  P[0][0] = 0.1f;
453  P[1][1] = 0.1f;
454  P[2][2] = 0.1f;
455  // velocities
456  P[3][3] = sq(frontend->_gpsHorizVelNoise);
457  P[4][4] = P[3][3];
458  P[5][5] = sq(frontend->_gpsVertVelNoise);
459  // positions
460  P[6][6] = sq(frontend->_gpsHorizPosNoise);
461  P[7][7] = P[6][6];
462  P[8][8] = sq(frontend->_baroAltNoise);
463  // gyro delta angle biases
465  P[10][10] = P[9][9];
466  P[11][11] = P[9][9];
467  // gyro scale factor biases
468  P[12][12] = sq(1e-3);
469  P[13][13] = P[12][12];
470  P[14][14] = P[12][12];
471  // Z delta velocity bias
473  // earth magnetic field
474  P[16][16] = 0.0f;
475  P[17][17] = P[16][16];
476  P[18][18] = P[16][16];
477  // body magnetic field
478  P[19][19] = 0.0f;
479  P[20][20] = P[19][19];
480  P[21][21] = P[19][19];
481  // wind velocities
482  P[22][22] = 0.0f;
483  P[23][23] = P[22][22];
484 
485  // optical flow ground height covariance
486  Popt = 0.25f;
487 }
488 
489 /********************************************************
490 * UPDATE FUNCTIONS *
491 ********************************************************/
492 // Update Filter States - this should be called whenever new IMU data is available
493 void NavEKF2_core::UpdateFilter(bool predict)
494 {
495  // Set the flag to indicate to the filter that the front-end has given permission for a new state prediction cycle to be started
496  startPredictEnabled = predict;
497 
498  // don't run filter updates if states have not been initialised
499  if (!statesInitialised) {
500  return;
501  }
502 
503  // start the timer used for load measurement
504 #if EK2_DISABLE_INTERRUPTS
505  irqstate_t istate = irqsave();
506 #endif
508 
509  // TODO - in-flight restart method
510 
511  //get starting time for update step
513 
514  // Check arm status and perform required checks and mode changes
516 
517  // read IMU data as delta angles and velocities
518  readIMUData();
519 
520  // Run the EKF equations to estimate at the fusion time horizon if new IMU data is available in the buffer
521  if (runUpdates) {
522  // Predict states using IMU data from the delayed time horizon
524 
525  // Predict the covariance growth
527 
528  // Update states using magnetometer data
529  SelectMagFusion();
530 
531  // Update states using GPS and altimeter data
533 
534  // Update states using range beacon data
536 
537  // Update states using optical flow data
539 
540  // Update states using airspeed data
541  SelectTasFusion();
542 
543  // Update states using sideslip constraint assumption for fly-forward vehicles
545 
546  // Update the filter status
548  }
549 
550  // Wind output forward from the fusion to output time horizon
552 
553  // stop the timer used for load measurement
555 #if EK2_DISABLE_INTERRUPTS
556  irqrestore(istate);
557 #endif
558 }
559 
560 void NavEKF2_core::correctDeltaAngle(Vector3f &delAng, float delAngDT)
561 {
562  delAng.x = delAng.x * stateStruct.gyro_scale.x;
563  delAng.y = delAng.y * stateStruct.gyro_scale.y;
564  delAng.z = delAng.z * stateStruct.gyro_scale.z;
565  delAng -= stateStruct.gyro_bias * (delAngDT / dtEkfAvg);
566 }
567 
568 void NavEKF2_core::correctDeltaVelocity(Vector3f &delVel, float delVelDT)
569 {
570  delVel.z -= stateStruct.accel_zbias * (delVelDT / dtEkfAvg);
571 }
572 
573 /*
574  * Update the quaternion, velocity and position states using delayed IMU measurements
575  * because the EKF is running on a delayed time horizon. Note that the quaternion is
576  * not used by the EKF equations, which instead estimate the error in the attitude of
577  * the vehicle when each observtion is fused. This attitude error is then used to correct
578  * the quaternion.
579 */
581 {
582  // update the quaternion states by rotating from the previous attitude through
583  // the delta angle rotation quaternion and normalise
584  // apply correction for earth's rotation rate
585  // % * - and + operators have been overloaded
588 
589  // transform body delta velocities to delta velocities in the nav frame
590  // use the nav frame from previous time step as the delta velocities
591  // have been rotated into that frame
592  // * and + operators have been overloaded
593  Vector3f delVelNav; // delta velocity vector in earth axes
595  delVelNav.z += GRAVITY_MSS*imuDataDelayed.delVelDT;
596 
597  // calculate the body to nav cosine matrix
599 
600  // calculate the rate of change of velocity (used for launch detect and other functions)
601  velDotNED = delVelNav / imuDataDelayed.delVelDT;
602 
603  // apply a first order lowpass filter
604  velDotNEDfilt = velDotNED * 0.05f + velDotNEDfilt * 0.95f;
605 
606  // calculate a magnitude of the filtered nav acceleration (required for GPS
607  // variance estimation)
610 
611  // if we are not aiding, then limit the horizontal magnitude of acceleration
612  // to prevent large manoeuvre transients disturbing the attitude
613  if ((PV_AidingMode == AID_NONE) && (accNavMagHoriz > 5.0f)) {
614  float gain = 5.0f/accNavMagHoriz;
615  delVelNav.x *= gain;
616  delVelNav.y *= gain;
617  }
618 
619  // save velocity for use in trapezoidal integration for position calcuation
620  Vector3f lastVelocity = stateStruct.velocity;
621 
622  // sum delta velocities to get velocity
623  stateStruct.velocity += delVelNav;
624 
625  // apply a trapezoidal integration to velocities to calculate position
626  stateStruct.position += (stateStruct.velocity + lastVelocity) * (imuDataDelayed.delVelDT*0.5f);
627 
628  // accumulate the bias delta angle and time since last reset by an OF measurement arrival
631 
632  // limit states to protect against divergence
633  ConstrainStates();
634 }
635 
636 /*
637  * Propagate PVA solution forward from the fusion time horizon to the current time horizon
638  * using simple observer which performs two functions:
639  * 1) Corrects for the delayed time horizon used by the EKF.
640  * 2) Applies a LPF to state corrections to prevent 'stepping' in states due to measurement
641  * fusion introducing unwanted noise into the control loops.
642  * The inspiration for using a complementary filter to correct for time delays in the EKF
643  * is based on the work by A Khosravian.
644  *
645  * "Recursive Attitude Estimation in the Presence of Multi-rate and Multi-delay Vector Measurements"
646  * A Khosravian, J Trumpf, R Mahony, T Hamel, Australian National University
647 */
649 {
650  // apply corrections to the IMU data
651  Vector3f delAngNewCorrected = imuDataNew.delAng;
652  Vector3f delVelNewCorrected = imuDataNew.delVel;
653  correctDeltaAngle(delAngNewCorrected, imuDataNew.delAngDT);
654  correctDeltaVelocity(delVelNewCorrected, imuDataNew.delVelDT);
655 
656  // apply corections to track EKF solution
657  Vector3f delAng = delAngNewCorrected + delAngCorrection;
658 
659  // convert the rotation vector to its equivalent quaternion
660  Quaternion deltaQuat;
661  deltaQuat.from_axis_angle(delAng);
662 
663  // update the quaternion states by rotating from the previous attitude through
664  // the delta angle rotation quaternion and normalise
665  outputDataNew.quat *= deltaQuat;
667 
668  // calculate the body to nav cosine matrix
669  Matrix3f Tbn_temp;
671 
672  // transform body delta velocities to delta velocities in the nav frame
673  Vector3f delVelNav = Tbn_temp*delVelNewCorrected;
674  delVelNav.z += GRAVITY_MSS*imuDataNew.delVelDT;
675 
676  // save velocity for use in trapezoidal integration for position calcuation
677  Vector3f lastVelocity = outputDataNew.velocity;
678 
679  // sum delta velocities to get velocity
680  outputDataNew.velocity += delVelNav;
681 
682  // apply a trapezoidal integration to velocities to calculate position
683  outputDataNew.position += (outputDataNew.velocity + lastVelocity) * (imuDataNew.delVelDT*0.5f);
684 
685  // If the IMU accelerometer is offset from the body frame origin, then calculate corrections
686  // that can be added to the EKF velocity and position outputs so that they represent the velocity
687  // and position of the body frame origin.
688  // Note the * operator has been overloaded to operate as a dot product
689  if (!accelPosOffset.is_zero()) {
690  // calculate the average angular rate across the last IMU update
691  // note delAngDT is prevented from being zero in readIMUData()
692  Vector3f angRate = imuDataNew.delAng * (1.0f/imuDataNew.delAngDT);
693 
694  // Calculate the velocity of the body frame origin relative to the IMU in body frame
695  // and rotate into earth frame. Note % operator has been overloaded to perform a cross product
696  Vector3f velBodyRelIMU = angRate % (- accelPosOffset);
697  velOffsetNED = Tbn_temp * velBodyRelIMU;
698 
699  // calculate the earth frame position of the body frame origin relative to the IMU
700  posOffsetNED = Tbn_temp * (- accelPosOffset);
701  } else {
702  velOffsetNED.zero();
703  posOffsetNED.zero();
704  }
705 
706  // store INS states in a ring buffer that with the same length and time coordinates as the IMU data buffer
707  if (runUpdates) {
708  // store the states at the output time horizon
709  storedOutput[storedIMU.get_youngest_index()] = outputDataNew;
710 
711  // recall the states from the fusion time horizon
712  outputDataDelayed = storedOutput[storedIMU.get_oldest_index()];
713 
714  // compare quaternion data with EKF quaternion at the fusion time horizon and calculate correction
715 
716  // divide the demanded quaternion by the estimated to get the error
718 
719  // Convert to a delta rotation using a small angle approximation
720  quatErr.normalize();
721  Vector3f deltaAngErr;
722  float scaler;
723  if (quatErr[0] >= 0.0f) {
724  scaler = 2.0f;
725  } else {
726  scaler = -2.0f;
727  }
728  deltaAngErr.x = scaler * quatErr[1];
729  deltaAngErr.y = scaler * quatErr[2];
730  deltaAngErr.z = scaler * quatErr[3];
731 
732  // calculate a gain that provides tight tracking of the estimator states and
733  // adjust for changes in time delay to maintain consistent damping ratio of ~0.7
734  float timeDelay = 1e-3f * (float)(imuDataNew.time_ms - imuDataDelayed.time_ms);
735  timeDelay = fmaxf(timeDelay, dtIMUavg);
736  float errorGain = 0.5f / timeDelay;
737 
738  // calculate a corrrection to the delta angle
739  // that will cause the INS to track the EKF quaternions
740  delAngCorrection = deltaAngErr * errorGain * dtIMUavg;
741 
742  // calculate velocity and position tracking errors
745 
746  // collect magnitude tracking error for diagnostics
747  outputTrackError.x = deltaAngErr.length();
748  outputTrackError.y = velErr.length();
749  outputTrackError.z = posErr.length();
750 
751  // convert user specified time constant from centi-seconds to seconds
752  float tauPosVel = constrain_float(0.01f*(float)frontend->_tauVelPosOutput, 0.1f, 0.5f);
753 
754  // calculate a gain to track the EKF position states with the specified time constant
755  float velPosGain = dtEkfAvg / constrain_float(tauPosVel, dtEkfAvg, 10.0f);
756 
757  // use a PI feedback to calculate a correction that will be applied to the output state history
758  posErrintegral += posErr;
759  velErrintegral += velErr;
760  Vector3f velCorrection = velErr * velPosGain + velErrintegral * sq(velPosGain) * 0.1f;
761  Vector3f posCorrection = posErr * velPosGain + posErrintegral * sq(velPosGain) * 0.1f;
762 
763  // loop through the output filter state history and apply the corrections to the velocity and position states
764  // this method is too expensive to use for the attitude states due to the quaternion operations required
765  // but does not introduce a time delay in the 'correction loop' and allows smaller tracking time constants
766  // to be used
767  output_elements outputStates;
768  for (unsigned index=0; index < imu_buffer_length; index++) {
769  outputStates = storedOutput[index];
770 
771  // a constant velocity correction is applied
772  outputStates.velocity += velCorrection;
773 
774  // a constant position correction is applied
775  outputStates.position += posCorrection;
776 
777  // push the updated data to the buffer
778  storedOutput[index] = outputStates;
779  }
780 
781  // update output state to corrected values
782  outputDataNew = storedOutput[storedIMU.get_youngest_index()];
783 
784  }
785 }
786 
787 /*
788  * Calculate the predicted state covariance matrix using algebraic equations generated with Matlab symbolic toolbox.
789  * The script file used to generate these and other equations in this filter can be found here:
790  * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
791 */
793 {
795  float windVelSigma; // wind velocity 1-sigma process noise - m/s
796  float dAngBiasSigma;// delta angle bias 1-sigma process noise - rad/s
797  float dVelBiasSigma;// delta velocity bias 1-sigma process noise - m/s
798  float dAngScaleSigma;// delta angle scale factor 1-Sigma process noise
799  float magEarthSigma;// earth magnetic field 1-sigma process noise
800  float magBodySigma; // body magnetic field 1-sigma process noise
801  float daxNoise; // X axis delta angle noise variance rad^2
802  float dayNoise; // Y axis delta angle noise variance rad^2
803  float dazNoise; // Z axis delta angle noise variance rad^2
804  float dvxNoise; // X axis delta velocity variance noise (m/s)^2
805  float dvyNoise; // Y axis delta velocity variance noise (m/s)^2
806  float dvzNoise; // Z axis delta velocity variance noise (m/s)^2
807  float dvx; // X axis delta velocity (m/s)
808  float dvy; // Y axis delta velocity (m/s)
809  float dvz; // Z axis delta velocity (m/s)
810  float dax; // X axis delta angle (rad)
811  float day; // Y axis delta angle (rad)
812  float daz; // Z axis delta angle (rad)
813  float q0; // attitude quaternion
814  float q1; // attitude quaternion
815  float q2; // attitude quaternion
816  float q3; // attitude quaternion
817  float dax_b; // X axis delta angle measurement bias (rad)
818  float day_b; // Y axis delta angle measurement bias (rad)
819  float daz_b; // Z axis delta angle measurement bias (rad)
820  float dax_s; // X axis delta angle measurement scale factor
821  float day_s; // Y axis delta angle measurement scale factor
822  float daz_s; // Z axis delta angle measurement scale factor
823  float dvz_b; // Z axis delta velocity measurement bias (rad)
824 
825  // calculate covariance prediction process noise
826  // use filtered height rate to increase wind process noise when climbing or descending
827  // this allows for wind gradient effects.
828  // filter height rate using a 10 second time constant filter
830  float alpha = 0.1f * dt;
831  hgtRate = hgtRate * (1.0f - alpha) - stateStruct.velocity.z * alpha;
832 
833  // use filtered height rate to increase wind process noise when climbing or descending
834  // this allows for wind gradient effects.
835  windVelSigma = dt * constrain_float(frontend->_windVelProcessNoise, 0.0f, 1.0f) * (1.0f + constrain_float(frontend->_wndVarHgtRateScale, 0.0f, 1.0f) * fabsf(hgtRate));
836  dAngBiasSigma = sq(dt) * constrain_float(frontend->_gyroBiasProcessNoise, 0.0f, 1.0f);
837  dVelBiasSigma = sq(dt) * constrain_float(frontend->_accelBiasProcessNoise, 0.0f, 1.0f);
838  dAngScaleSigma = dt * constrain_float(frontend->_gyroScaleProcessNoise, 0.0f, 1.0f);
839  magEarthSigma = dt * constrain_float(frontend->_magEarthProcessNoise, 0.0f, 1.0f);
840  magBodySigma = dt * constrain_float(frontend->_magBodyProcessNoise, 0.0f, 1.0f);
841  for (uint8_t i= 0; i<=8; i++) processNoise[i] = 0.0f;
842  for (uint8_t i=9; i<=11; i++) processNoise[i] = dAngBiasSigma;
843  for (uint8_t i=12; i<=14; i++) processNoise[i] = dAngScaleSigma;
845  processNoise[15] = 0.0f;
846  } else {
847  processNoise[15] = dVelBiasSigma;
848  }
849  for (uint8_t i=16; i<=18; i++) processNoise[i] = magEarthSigma;
850  for (uint8_t i=19; i<=21; i++) processNoise[i] = magBodySigma;
851  for (uint8_t i=22; i<=23; i++) processNoise[i] = windVelSigma;
852 
853  for (uint8_t i= 0; i<=stateIndexLim; i++) processNoise[i] = sq(processNoise[i]);
854 
855  // set variables used to calculate covariance growth
856  dvx = imuDataDelayed.delVel.x;
857  dvy = imuDataDelayed.delVel.y;
858  dvz = imuDataDelayed.delVel.z;
859  dax = imuDataDelayed.delAng.x;
860  day = imuDataDelayed.delAng.y;
861  daz = imuDataDelayed.delAng.z;
862  q0 = stateStruct.quat[0];
863  q1 = stateStruct.quat[1];
864  q2 = stateStruct.quat[2];
865  q3 = stateStruct.quat[3];
866  dax_b = stateStruct.gyro_bias.x;
867  day_b = stateStruct.gyro_bias.y;
868  daz_b = stateStruct.gyro_bias.z;
869  dax_s = stateStruct.gyro_scale.x;
870  day_s = stateStruct.gyro_scale.y;
871  daz_s = stateStruct.gyro_scale.z;
872  dvz_b = stateStruct.accel_zbias;
873  float _gyrNoise = constrain_float(frontend->_gyrNoise, 0.0f, 1.0f);
874  daxNoise = dayNoise = dazNoise = sq(dt*_gyrNoise);
875  float _accNoise = constrain_float(frontend->_accNoise, 0.0f, 10.0f);
876  dvxNoise = dvyNoise = dvzNoise = sq(dt*_accNoise);
877 
878  // calculate the predicted covariance due to inertial sensor error propagation
879  // we calculate the upper diagonal and copy to take advantage of symmetry
880  SF[0] = daz_b/2 - (daz*daz_s)/2;
881  SF[1] = day_b/2 - (day*day_s)/2;
882  SF[2] = dax_b/2 - (dax*dax_s)/2;
883  SF[3] = q3/2 - (q0*SF[0])/2 + (q1*SF[1])/2 - (q2*SF[2])/2;
884  SF[4] = q0/2 - (q1*SF[2])/2 - (q2*SF[1])/2 + (q3*SF[0])/2;
885  SF[5] = q1/2 + (q0*SF[2])/2 - (q2*SF[0])/2 - (q3*SF[1])/2;
886  SF[6] = q3/2 + (q0*SF[0])/2 - (q1*SF[1])/2 - (q2*SF[2])/2;
887  SF[7] = q0/2 - (q1*SF[2])/2 + (q2*SF[1])/2 - (q3*SF[0])/2;
888  SF[8] = q0/2 + (q1*SF[2])/2 - (q2*SF[1])/2 - (q3*SF[0])/2;
889  SF[9] = q2/2 + (q0*SF[1])/2 + (q1*SF[0])/2 + (q3*SF[2])/2;
890  SF[10] = q2/2 - (q0*SF[1])/2 - (q1*SF[0])/2 + (q3*SF[2])/2;
891  SF[11] = q2/2 + (q0*SF[1])/2 - (q1*SF[0])/2 - (q3*SF[2])/2;
892  SF[12] = q1/2 + (q0*SF[2])/2 + (q2*SF[0])/2 + (q3*SF[1])/2;
893  SF[13] = q1/2 - (q0*SF[2])/2 + (q2*SF[0])/2 - (q3*SF[1])/2;
894  SF[14] = q3/2 + (q0*SF[0])/2 + (q1*SF[1])/2 + (q2*SF[2])/2;
895  SF[15] = - sq(q0) - sq(q1) - sq(q2) - sq(q3);
896  SF[16] = dvz_b - dvz;
897  SF[17] = dvx;
898  SF[18] = dvy;
899  SF[19] = sq(q2);
900  SF[20] = SF[19] - sq(q0) + sq(q1) - sq(q3);
901  SF[21] = SF[19] + sq(q0) - sq(q1) - sq(q3);
902  SF[22] = 2*q0*q1 - 2*q2*q3;
903  SF[23] = SF[19] - sq(q0) - sq(q1) + sq(q3);
904  SF[24] = 2*q1*q2;
905 
906  SG[0] = - sq(q0) - sq(q1) - sq(q2) - sq(q3);
907  SG[1] = sq(q3);
908  SG[2] = sq(q2);
909  SG[3] = sq(q1);
910  SG[4] = sq(q0);
911 
912  SQ[0] = - dvyNoise*(2*q0*q1 + 2*q2*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvzNoise*(2*q0*q1 - 2*q2*q3)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxNoise*(2*q0*q2 - 2*q1*q3)*(2*q0*q3 + 2*q1*q2);
913  SQ[1] = dvxNoise*(2*q0*q2 - 2*q1*q3)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvzNoise*(2*q0*q2 + 2*q1*q3)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyNoise*(2*q0*q1 + 2*q2*q3)*(2*q0*q3 - 2*q1*q2);
914  SQ[2] = dvyNoise*(2*q0*q3 - 2*q1*q2)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxNoise*(2*q0*q3 + 2*q1*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) - dvzNoise*(2*q0*q1 - 2*q2*q3)*(2*q0*q2 + 2*q1*q3);
915  SQ[3] = sq(SG[0]);
916  SQ[4] = 2*q2*q3;
917  SQ[5] = 2*q1*q3;
918  SQ[6] = 2*q1*q2;
919  SQ[7] = SG[4];
920 
921  SPP[0] = SF[17]*(2*q0*q1 + 2*q2*q3) + SF[18]*(2*q0*q2 - 2*q1*q3);
922  SPP[1] = SF[18]*(2*q0*q2 + 2*q1*q3) + SF[16]*(SF[24] - 2*q0*q3);
923  SPP[2] = 2*q3*SF[8] + 2*q1*SF[11] - 2*q0*SF[14] - 2*q2*SF[13];
924  SPP[3] = 2*q1*SF[7] + 2*q2*SF[6] - 2*q0*SF[12] - 2*q3*SF[10];
925  SPP[4] = 2*q0*SF[6] - 2*q3*SF[7] - 2*q1*SF[10] + 2*q2*SF[12];
926  SPP[5] = 2*q0*SF[8] + 2*q2*SF[11] + 2*q1*SF[13] + 2*q3*SF[14];
927  SPP[6] = 2*q0*SF[7] + 2*q3*SF[6] + 2*q2*SF[10] + 2*q1*SF[12];
928  SPP[7] = SF[18]*SF[20] - SF[16]*(2*q0*q1 + 2*q2*q3);
929  SPP[8] = 2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9];
930  SPP[9] = 2*q0*SF[5] - 2*q1*SF[4] - 2*q2*SF[3] + 2*q3*SF[9];
931  SPP[10] = SF[17]*SF[20] + SF[16]*(2*q0*q2 - 2*q1*q3);
932  SPP[11] = SF[17]*SF[21] - SF[18]*(SF[24] + 2*q0*q3);
933  SPP[12] = SF[17]*SF[22] - SF[16]*(SF[24] + 2*q0*q3);
934  SPP[13] = 2*q0*SF[4] + 2*q1*SF[5] + 2*q3*SF[3] + 2*q2*SF[9];
935  SPP[14] = 2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13];
936  SPP[15] = SF[18]*SF[23] + SF[17]*(SF[24] - 2*q0*q3);
937  SPP[16] = daz*SF[19] + daz*sq(q0) + daz*sq(q1) + daz*sq(q3);
938  SPP[17] = day*SF[19] + day*sq(q0) + day*sq(q1) + day*sq(q3);
939  SPP[18] = dax*SF[19] + dax*sq(q0) + dax*sq(q1) + dax*sq(q3);
940  SPP[19] = SF[16]*SF[23] - SF[17]*(2*q0*q2 + 2*q1*q3);
941  SPP[20] = SF[16]*SF[21] - SF[18]*SF[22];
942  SPP[21] = 2*q0*q2 + 2*q1*q3;
943  SPP[22] = SF[15];
944 
945  if (inhibitMagStates) {
946  zeroRows(P,16,21);
947  zeroCols(P,16,21);
948  } else if (inhibitWindStates) {
949  zeroRows(P,22,23);
950  zeroCols(P,22,23);
951  }
952 
953  nextP[0][0] = daxNoise*SQ[3] + SPP[5]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[9][0]*SPP[22] + P[12][0]*SPP[18] + P[2][0]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9])) - SPP[4]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[9][1]*SPP[22] + P[12][1]*SPP[18] + P[2][1]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9])) + SPP[8]*(P[0][2]*SPP[5] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18] - P[1][2]*(2*q0*SF[6] - 2*q3*SF[7] - 2*q1*SF[10] + 2*q2*SF[12])) + SPP[22]*(P[0][9]*SPP[5] - P[1][9]*SPP[4] + P[9][9]*SPP[22] + P[12][9]*SPP[18] + P[2][9]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9])) + SPP[18]*(P[0][12]*SPP[5] - P[1][12]*SPP[4] + P[9][12]*SPP[22] + P[12][12]*SPP[18] + P[2][12]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9]));
954  nextP[0][1] = SPP[6]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) - SPP[2]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[22]*(P[0][10]*SPP[5] - P[1][10]*SPP[4] + P[2][10]*SPP[8] + P[9][10]*SPP[22] + P[12][10]*SPP[18]) + SPP[17]*(P[0][13]*SPP[5] - P[1][13]*SPP[4] + P[2][13]*SPP[8] + P[9][13]*SPP[22] + P[12][13]*SPP[18]) - (2*q0*SF[5] - 2*q1*SF[4] - 2*q2*SF[3] + 2*q3*SF[9])*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]);
955  nextP[1][1] = dayNoise*SQ[3] - SPP[2]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[6]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) - SPP[9]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[22]*(P[1][10]*SPP[6] - P[0][10]*SPP[2] - P[2][10]*SPP[9] + P[10][10]*SPP[22] + P[13][10]*SPP[17]) + SPP[17]*(P[1][13]*SPP[6] - P[0][13]*SPP[2] - P[2][13]*SPP[9] + P[10][13]*SPP[22] + P[13][13]*SPP[17]);
956  nextP[0][2] = SPP[13]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) - SPP[3]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[22]*(P[0][11]*SPP[5] - P[1][11]*SPP[4] + P[2][11]*SPP[8] + P[9][11]*SPP[22] + P[12][11]*SPP[18]) + SPP[16]*(P[0][14]*SPP[5] - P[1][14]*SPP[4] + P[2][14]*SPP[8] + P[9][14]*SPP[22] + P[12][14]*SPP[18]) + (2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13])*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]);
957  nextP[1][2] = SPP[13]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) - SPP[3]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[22]*(P[1][11]*SPP[6] - P[0][11]*SPP[2] - P[2][11]*SPP[9] + P[10][11]*SPP[22] + P[13][11]*SPP[17]) + SPP[16]*(P[1][14]*SPP[6] - P[0][14]*SPP[2] - P[2][14]*SPP[9] + P[10][14]*SPP[22] + P[13][14]*SPP[17]) + (2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13])*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]);
958  nextP[2][2] = dazNoise*SQ[3] - SPP[3]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[14]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[13]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) + SPP[22]*(P[0][11]*SPP[14] - P[1][11]*SPP[3] + P[2][11]*SPP[13] + P[11][11]*SPP[22] + P[14][11]*SPP[16]) + SPP[16]*(P[0][14]*SPP[14] - P[1][14]*SPP[3] + P[2][14]*SPP[13] + P[11][14]*SPP[22] + P[14][14]*SPP[16]);
959  nextP[0][3] = P[0][3]*SPP[5] - P[1][3]*SPP[4] + P[2][3]*SPP[8] + P[9][3]*SPP[22] + P[12][3]*SPP[18] + SPP[1]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[15]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) - SPP[21]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) + (SF[16]*SF[23] - SF[17]*SPP[21])*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]);
960  nextP[1][3] = P[1][3]*SPP[6] - P[0][3]*SPP[2] - P[2][3]*SPP[9] + P[10][3]*SPP[22] + P[13][3]*SPP[17] + SPP[1]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[15]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) - SPP[21]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) + (SF[16]*SF[23] - SF[17]*SPP[21])*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]);
961  nextP[2][3] = P[0][3]*SPP[14] - P[1][3]*SPP[3] + P[2][3]*SPP[13] + P[11][3]*SPP[22] + P[14][3]*SPP[16] + SPP[1]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[15]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) - SPP[21]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) + (SF[16]*SF[23] - SF[17]*SPP[21])*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]);
962  nextP[3][3] = P[3][3] + P[0][3]*SPP[1] + P[1][3]*SPP[19] + P[2][3]*SPP[15] - P[15][3]*SPP[21] + dvyNoise*sq(SQ[6] - 2*q0*q3) + dvzNoise*sq(SQ[5] + 2*q0*q2) + SPP[1]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[19]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]) + SPP[15]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]) - SPP[21]*(P[3][15] + P[0][15]*SPP[1] + P[2][15]*SPP[15] - P[15][15]*SPP[21] + P[1][15]*(SF[16]*SF[23] - SF[17]*SPP[21])) + dvxNoise*sq(SG[1] + SG[2] - SG[3] - SQ[7]);
963  nextP[0][4] = P[0][4]*SPP[5] - P[1][4]*SPP[4] + P[2][4]*SPP[8] + P[9][4]*SPP[22] + P[12][4]*SPP[18] + SF[22]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) + SPP[12]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[20]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[11]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]);
964  nextP[1][4] = P[1][4]*SPP[6] - P[0][4]*SPP[2] - P[2][4]*SPP[9] + P[10][4]*SPP[22] + P[13][4]*SPP[17] + SF[22]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) + SPP[12]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[20]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[11]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]);
965  nextP[2][4] = P[0][4]*SPP[14] - P[1][4]*SPP[3] + P[2][4]*SPP[13] + P[11][4]*SPP[22] + P[14][4]*SPP[16] + SF[22]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) + SPP[12]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[20]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[11]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]);
966  nextP[3][4] = P[3][4] + SQ[2] + P[0][4]*SPP[1] + P[1][4]*SPP[19] + P[2][4]*SPP[15] - P[15][4]*SPP[21] + SF[22]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) + SPP[12]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]) + SPP[20]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[11]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]);
967  nextP[4][4] = P[4][4] + P[15][4]*SF[22] + P[0][4]*SPP[20] + P[1][4]*SPP[12] + P[2][4]*SPP[11] + dvxNoise*sq(SQ[6] + 2*q0*q3) + dvzNoise*sq(SQ[4] - 2*q0*q1) + SF[22]*(P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]) + SPP[12]*(P[4][1] + P[15][1]*SF[22] + P[0][1]*SPP[20] + P[1][1]*SPP[12] + P[2][1]*SPP[11]) + SPP[20]*(P[4][0] + P[15][0]*SF[22] + P[0][0]*SPP[20] + P[1][0]*SPP[12] + P[2][0]*SPP[11]) + SPP[11]*(P[4][2] + P[15][2]*SF[22] + P[0][2]*SPP[20] + P[1][2]*SPP[12] + P[2][2]*SPP[11]) + dvyNoise*sq(SG[1] - SG[2] + SG[3] - SQ[7]);
968  nextP[0][5] = P[0][5]*SPP[5] - P[1][5]*SPP[4] + P[2][5]*SPP[8] + P[9][5]*SPP[22] + P[12][5]*SPP[18] + SF[20]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) - SPP[7]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[0]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) + SPP[10]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]);
969  nextP[1][5] = P[1][5]*SPP[6] - P[0][5]*SPP[2] - P[2][5]*SPP[9] + P[10][5]*SPP[22] + P[13][5]*SPP[17] + SF[20]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) - SPP[7]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[0]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[10]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]);
970  nextP[2][5] = P[0][5]*SPP[14] - P[1][5]*SPP[3] + P[2][5]*SPP[13] + P[11][5]*SPP[22] + P[14][5]*SPP[16] + SF[20]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) - SPP[7]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[0]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) + SPP[10]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]);
971  nextP[3][5] = P[3][5] + SQ[1] + P[0][5]*SPP[1] + P[1][5]*SPP[19] + P[2][5]*SPP[15] - P[15][5]*SPP[21] + SF[20]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) - SPP[7]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[0]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]) + SPP[10]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]);
972  nextP[4][5] = P[4][5] + SQ[0] + P[15][5]*SF[22] + P[0][5]*SPP[20] + P[1][5]*SPP[12] + P[2][5]*SPP[11] + SF[20]*(P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]) - SPP[7]*(P[4][0] + P[15][0]*SF[22] + P[0][0]*SPP[20] + P[1][0]*SPP[12] + P[2][0]*SPP[11]) + SPP[0]*(P[4][2] + P[15][2]*SF[22] + P[0][2]*SPP[20] + P[1][2]*SPP[12] + P[2][2]*SPP[11]) + SPP[10]*(P[4][1] + P[15][1]*SF[22] + P[0][1]*SPP[20] + P[1][1]*SPP[12] + P[2][1]*SPP[11]);
973  nextP[5][5] = P[5][5] + P[15][5]*SF[20] - P[0][5]*SPP[7] + P[1][5]*SPP[10] + P[2][5]*SPP[0] + dvxNoise*sq(SQ[5] - 2*q0*q2) + dvyNoise*sq(SQ[4] + 2*q0*q1) + SF[20]*(P[5][15] + P[15][15]*SF[20] - P[0][15]*SPP[7] + P[1][15]*SPP[10] + P[2][15]*SPP[0]) - SPP[7]*(P[5][0] + P[15][0]*SF[20] - P[0][0]*SPP[7] + P[1][0]*SPP[10] + P[2][0]*SPP[0]) + SPP[0]*(P[5][2] + P[15][2]*SF[20] - P[0][2]*SPP[7] + P[1][2]*SPP[10] + P[2][2]*SPP[0]) + SPP[10]*(P[5][1] + P[15][1]*SF[20] - P[0][1]*SPP[7] + P[1][1]*SPP[10] + P[2][1]*SPP[0]) + dvzNoise*sq(SG[1] - SG[2] - SG[3] + SQ[7]);
974  nextP[0][6] = P[0][6]*SPP[5] - P[1][6]*SPP[4] + P[2][6]*SPP[8] + P[9][6]*SPP[22] + P[12][6]*SPP[18] + dt*(P[0][3]*SPP[5] - P[1][3]*SPP[4] + P[2][3]*SPP[8] + P[9][3]*SPP[22] + P[12][3]*SPP[18]);
975  nextP[1][6] = P[1][6]*SPP[6] - P[0][6]*SPP[2] - P[2][6]*SPP[9] + P[10][6]*SPP[22] + P[13][6]*SPP[17] + dt*(P[1][3]*SPP[6] - P[0][3]*SPP[2] - P[2][3]*SPP[9] + P[10][3]*SPP[22] + P[13][3]*SPP[17]);
976  nextP[2][6] = P[0][6]*SPP[14] - P[1][6]*SPP[3] + P[2][6]*SPP[13] + P[11][6]*SPP[22] + P[14][6]*SPP[16] + dt*(P[0][3]*SPP[14] - P[1][3]*SPP[3] + P[2][3]*SPP[13] + P[11][3]*SPP[22] + P[14][3]*SPP[16]);
977  nextP[3][6] = P[3][6] + P[0][6]*SPP[1] + P[1][6]*SPP[19] + P[2][6]*SPP[15] - P[15][6]*SPP[21] + dt*(P[3][3] + P[0][3]*SPP[1] + P[1][3]*SPP[19] + P[2][3]*SPP[15] - P[15][3]*SPP[21]);
978  nextP[4][6] = P[4][6] + P[15][6]*SF[22] + P[0][6]*SPP[20] + P[1][6]*SPP[12] + P[2][6]*SPP[11] + dt*(P[4][3] + P[15][3]*SF[22] + P[0][3]*SPP[20] + P[1][3]*SPP[12] + P[2][3]*SPP[11]);
979  nextP[5][6] = P[5][6] + P[15][6]*SF[20] - P[0][6]*SPP[7] + P[1][6]*SPP[10] + P[2][6]*SPP[0] + dt*(P[5][3] + P[15][3]*SF[20] - P[0][3]*SPP[7] + P[1][3]*SPP[10] + P[2][3]*SPP[0]);
980  nextP[6][6] = P[6][6] + P[3][6]*dt + dt*(P[6][3] + P[3][3]*dt);
981  nextP[0][7] = P[0][7]*SPP[5] - P[1][7]*SPP[4] + P[2][7]*SPP[8] + P[9][7]*SPP[22] + P[12][7]*SPP[18] + dt*(P[0][4]*SPP[5] - P[1][4]*SPP[4] + P[2][4]*SPP[8] + P[9][4]*SPP[22] + P[12][4]*SPP[18]);
982  nextP[1][7] = P[1][7]*SPP[6] - P[0][7]*SPP[2] - P[2][7]*SPP[9] + P[10][7]*SPP[22] + P[13][7]*SPP[17] + dt*(P[1][4]*SPP[6] - P[0][4]*SPP[2] - P[2][4]*SPP[9] + P[10][4]*SPP[22] + P[13][4]*SPP[17]);
983  nextP[2][7] = P[0][7]*SPP[14] - P[1][7]*SPP[3] + P[2][7]*SPP[13] + P[11][7]*SPP[22] + P[14][7]*SPP[16] + dt*(P[0][4]*SPP[14] - P[1][4]*SPP[3] + P[2][4]*SPP[13] + P[11][4]*SPP[22] + P[14][4]*SPP[16]);
984  nextP[3][7] = P[3][7] + P[0][7]*SPP[1] + P[1][7]*SPP[19] + P[2][7]*SPP[15] - P[15][7]*SPP[21] + dt*(P[3][4] + P[0][4]*SPP[1] + P[1][4]*SPP[19] + P[2][4]*SPP[15] - P[15][4]*SPP[21]);
985  nextP[4][7] = P[4][7] + P[15][7]*SF[22] + P[0][7]*SPP[20] + P[1][7]*SPP[12] + P[2][7]*SPP[11] + dt*(P[4][4] + P[15][4]*SF[22] + P[0][4]*SPP[20] + P[1][4]*SPP[12] + P[2][4]*SPP[11]);
986  nextP[5][7] = P[5][7] + P[15][7]*SF[20] - P[0][7]*SPP[7] + P[1][7]*SPP[10] + P[2][7]*SPP[0] + dt*(P[5][4] + P[15][4]*SF[20] - P[0][4]*SPP[7] + P[1][4]*SPP[10] + P[2][4]*SPP[0]);
987  nextP[6][7] = P[6][7] + P[3][7]*dt + dt*(P[6][4] + P[3][4]*dt);
988  nextP[7][7] = P[7][7] + P[4][7]*dt + dt*(P[7][4] + P[4][4]*dt);
989  nextP[0][8] = P[0][8]*SPP[5] - P[1][8]*SPP[4] + P[2][8]*SPP[8] + P[9][8]*SPP[22] + P[12][8]*SPP[18] + dt*(P[0][5]*SPP[5] - P[1][5]*SPP[4] + P[2][5]*SPP[8] + P[9][5]*SPP[22] + P[12][5]*SPP[18]);
990  nextP[1][8] = P[1][8]*SPP[6] - P[0][8]*SPP[2] - P[2][8]*SPP[9] + P[10][8]*SPP[22] + P[13][8]*SPP[17] + dt*(P[1][5]*SPP[6] - P[0][5]*SPP[2] - P[2][5]*SPP[9] + P[10][5]*SPP[22] + P[13][5]*SPP[17]);
991  nextP[2][8] = P[0][8]*SPP[14] - P[1][8]*SPP[3] + P[2][8]*SPP[13] + P[11][8]*SPP[22] + P[14][8]*SPP[16] + dt*(P[0][5]*SPP[14] - P[1][5]*SPP[3] + P[2][5]*SPP[13] + P[11][5]*SPP[22] + P[14][5]*SPP[16]);
992  nextP[3][8] = P[3][8] + P[0][8]*SPP[1] + P[1][8]*SPP[19] + P[2][8]*SPP[15] - P[15][8]*SPP[21] + dt*(P[3][5] + P[0][5]*SPP[1] + P[1][5]*SPP[19] + P[2][5]*SPP[15] - P[15][5]*SPP[21]);
993  nextP[4][8] = P[4][8] + P[15][8]*SF[22] + P[0][8]*SPP[20] + P[1][8]*SPP[12] + P[2][8]*SPP[11] + dt*(P[4][5] + P[15][5]*SF[22] + P[0][5]*SPP[20] + P[1][5]*SPP[12] + P[2][5]*SPP[11]);
994  nextP[5][8] = P[5][8] + P[15][8]*SF[20] - P[0][8]*SPP[7] + P[1][8]*SPP[10] + P[2][8]*SPP[0] + dt*(P[5][5] + P[15][5]*SF[20] - P[0][5]*SPP[7] + P[1][5]*SPP[10] + P[2][5]*SPP[0]);
995  nextP[6][8] = P[6][8] + P[3][8]*dt + dt*(P[6][5] + P[3][5]*dt);
996  nextP[7][8] = P[7][8] + P[4][8]*dt + dt*(P[7][5] + P[4][5]*dt);
997  nextP[8][8] = P[8][8] + P[5][8]*dt + dt*(P[8][5] + P[5][5]*dt);
998  nextP[0][9] = P[0][9]*SPP[5] - P[1][9]*SPP[4] + P[2][9]*SPP[8] + P[9][9]*SPP[22] + P[12][9]*SPP[18];
999  nextP[1][9] = P[1][9]*SPP[6] - P[0][9]*SPP[2] - P[2][9]*SPP[9] + P[10][9]*SPP[22] + P[13][9]*SPP[17];
1000  nextP[2][9] = P[0][9]*SPP[14] - P[1][9]*SPP[3] + P[2][9]*SPP[13] + P[11][9]*SPP[22] + P[14][9]*SPP[16];
1001  nextP[3][9] = P[3][9] + P[0][9]*SPP[1] + P[1][9]*SPP[19] + P[2][9]*SPP[15] - P[15][9]*SPP[21];
1002  nextP[4][9] = P[4][9] + P[15][9]*SF[22] + P[0][9]*SPP[20] + P[1][9]*SPP[12] + P[2][9]*SPP[11];
1003  nextP[5][9] = P[5][9] + P[15][9]*SF[20] - P[0][9]*SPP[7] + P[1][9]*SPP[10] + P[2][9]*SPP[0];
1004  nextP[6][9] = P[6][9] + P[3][9]*dt;
1005  nextP[7][9] = P[7][9] + P[4][9]*dt;
1006  nextP[8][9] = P[8][9] + P[5][9]*dt;
1007  nextP[9][9] = P[9][9];
1008  nextP[0][10] = P[0][10]*SPP[5] - P[1][10]*SPP[4] + P[2][10]*SPP[8] + P[9][10]*SPP[22] + P[12][10]*SPP[18];
1009  nextP[1][10] = P[1][10]*SPP[6] - P[0][10]*SPP[2] - P[2][10]*SPP[9] + P[10][10]*SPP[22] + P[13][10]*SPP[17];
1010  nextP[2][10] = P[0][10]*SPP[14] - P[1][10]*SPP[3] + P[2][10]*SPP[13] + P[11][10]*SPP[22] + P[14][10]*SPP[16];
1011  nextP[3][10] = P[3][10] + P[0][10]*SPP[1] + P[1][10]*SPP[19] + P[2][10]*SPP[15] - P[15][10]*SPP[21];
1012  nextP[4][10] = P[4][10] + P[15][10]*SF[22] + P[0][10]*SPP[20] + P[1][10]*SPP[12] + P[2][10]*SPP[11];
1013  nextP[5][10] = P[5][10] + P[15][10]*SF[20] - P[0][10]*SPP[7] + P[1][10]*SPP[10] + P[2][10]*SPP[0];
1014  nextP[6][10] = P[6][10] + P[3][10]*dt;
1015  nextP[7][10] = P[7][10] + P[4][10]*dt;
1016  nextP[8][10] = P[8][10] + P[5][10]*dt;
1017  nextP[9][10] = P[9][10];
1018  nextP[10][10] = P[10][10];
1019  nextP[0][11] = P[0][11]*SPP[5] - P[1][11]*SPP[4] + P[2][11]*SPP[8] + P[9][11]*SPP[22] + P[12][11]*SPP[18];
1020  nextP[1][11] = P[1][11]*SPP[6] - P[0][11]*SPP[2] - P[2][11]*SPP[9] + P[10][11]*SPP[22] + P[13][11]*SPP[17];
1021  nextP[2][11] = P[0][11]*SPP[14] - P[1][11]*SPP[3] + P[2][11]*SPP[13] + P[11][11]*SPP[22] + P[14][11]*SPP[16];
1022  nextP[3][11] = P[3][11] + P[0][11]*SPP[1] + P[1][11]*SPP[19] + P[2][11]*SPP[15] - P[15][11]*SPP[21];
1023  nextP[4][11] = P[4][11] + P[15][11]*SF[22] + P[0][11]*SPP[20] + P[1][11]*SPP[12] + P[2][11]*SPP[11];
1024  nextP[5][11] = P[5][11] + P[15][11]*SF[20] - P[0][11]*SPP[7] + P[1][11]*SPP[10] + P[2][11]*SPP[0];
1025  nextP[6][11] = P[6][11] + P[3][11]*dt;
1026  nextP[7][11] = P[7][11] + P[4][11]*dt;
1027  nextP[8][11] = P[8][11] + P[5][11]*dt;
1028  nextP[9][11] = P[9][11];
1029  nextP[10][11] = P[10][11];
1030  nextP[11][11] = P[11][11];
1031  nextP[0][12] = P[0][12]*SPP[5] - P[1][12]*SPP[4] + P[2][12]*SPP[8] + P[9][12]*SPP[22] + P[12][12]*SPP[18];
1032  nextP[1][12] = P[1][12]*SPP[6] - P[0][12]*SPP[2] - P[2][12]*SPP[9] + P[10][12]*SPP[22] + P[13][12]*SPP[17];
1033  nextP[2][12] = P[0][12]*SPP[14] - P[1][12]*SPP[3] + P[2][12]*SPP[13] + P[11][12]*SPP[22] + P[14][12]*SPP[16];
1034  nextP[3][12] = P[3][12] + P[0][12]*SPP[1] + P[1][12]*SPP[19] + P[2][12]*SPP[15] - P[15][12]*SPP[21];
1035  nextP[4][12] = P[4][12] + P[15][12]*SF[22] + P[0][12]*SPP[20] + P[1][12]*SPP[12] + P[2][12]*SPP[11];
1036  nextP[5][12] = P[5][12] + P[15][12]*SF[20] - P[0][12]*SPP[7] + P[1][12]*SPP[10] + P[2][12]*SPP[0];
1037  nextP[6][12] = P[6][12] + P[3][12]*dt;
1038  nextP[7][12] = P[7][12] + P[4][12]*dt;
1039  nextP[8][12] = P[8][12] + P[5][12]*dt;
1040  nextP[9][12] = P[9][12];
1041  nextP[10][12] = P[10][12];
1042  nextP[11][12] = P[11][12];
1043  nextP[12][12] = P[12][12];
1044  nextP[0][13] = P[0][13]*SPP[5] - P[1][13]*SPP[4] + P[2][13]*SPP[8] + P[9][13]*SPP[22] + P[12][13]*SPP[18];
1045  nextP[1][13] = P[1][13]*SPP[6] - P[0][13]*SPP[2] - P[2][13]*SPP[9] + P[10][13]*SPP[22] + P[13][13]*SPP[17];
1046  nextP[2][13] = P[0][13]*SPP[14] - P[1][13]*SPP[3] + P[2][13]*SPP[13] + P[11][13]*SPP[22] + P[14][13]*SPP[16];
1047  nextP[3][13] = P[3][13] + P[0][13]*SPP[1] + P[1][13]*SPP[19] + P[2][13]*SPP[15] - P[15][13]*SPP[21];
1048  nextP[4][13] = P[4][13] + P[15][13]*SF[22] + P[0][13]*SPP[20] + P[1][13]*SPP[12] + P[2][13]*SPP[11];
1049  nextP[5][13] = P[5][13] + P[15][13]*SF[20] - P[0][13]*SPP[7] + P[1][13]*SPP[10] + P[2][13]*SPP[0];
1050  nextP[6][13] = P[6][13] + P[3][13]*dt;
1051  nextP[7][13] = P[7][13] + P[4][13]*dt;
1052  nextP[8][13] = P[8][13] + P[5][13]*dt;
1053  nextP[9][13] = P[9][13];
1054  nextP[10][13] = P[10][13];
1055  nextP[11][13] = P[11][13];
1056  nextP[12][13] = P[12][13];
1057  nextP[13][13] = P[13][13];
1058  nextP[0][14] = P[0][14]*SPP[5] - P[1][14]*SPP[4] + P[2][14]*SPP[8] + P[9][14]*SPP[22] + P[12][14]*SPP[18];
1059  nextP[1][14] = P[1][14]*SPP[6] - P[0][14]*SPP[2] - P[2][14]*SPP[9] + P[10][14]*SPP[22] + P[13][14]*SPP[17];
1060  nextP[2][14] = P[0][14]*SPP[14] - P[1][14]*SPP[3] + P[2][14]*SPP[13] + P[11][14]*SPP[22] + P[14][14]*SPP[16];
1061  nextP[3][14] = P[3][14] + P[0][14]*SPP[1] + P[1][14]*SPP[19] + P[2][14]*SPP[15] - P[15][14]*SPP[21];
1062  nextP[4][14] = P[4][14] + P[15][14]*SF[22] + P[0][14]*SPP[20] + P[1][14]*SPP[12] + P[2][14]*SPP[11];
1063  nextP[5][14] = P[5][14] + P[15][14]*SF[20] - P[0][14]*SPP[7] + P[1][14]*SPP[10] + P[2][14]*SPP[0];
1064  nextP[6][14] = P[6][14] + P[3][14]*dt;
1065  nextP[7][14] = P[7][14] + P[4][14]*dt;
1066  nextP[8][14] = P[8][14] + P[5][14]*dt;
1067  nextP[9][14] = P[9][14];
1068  nextP[10][14] = P[10][14];
1069  nextP[11][14] = P[11][14];
1070  nextP[12][14] = P[12][14];
1071  nextP[13][14] = P[13][14];
1072  nextP[14][14] = P[14][14];
1073  nextP[0][15] = P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18];
1074  nextP[1][15] = P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17];
1075  nextP[2][15] = P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16];
1076  nextP[3][15] = P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21];
1077  nextP[4][15] = P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11];
1078  nextP[5][15] = P[5][15] + P[15][15]*SF[20] - P[0][15]*SPP[7] + P[1][15]*SPP[10] + P[2][15]*SPP[0];
1079  nextP[6][15] = P[6][15] + P[3][15]*dt;
1080  nextP[7][15] = P[7][15] + P[4][15]*dt;
1081  nextP[8][15] = P[8][15] + P[5][15]*dt;
1082  nextP[9][15] = P[9][15];
1083  nextP[10][15] = P[10][15];
1084  nextP[11][15] = P[11][15];
1085  nextP[12][15] = P[12][15];
1086  nextP[13][15] = P[13][15];
1087  nextP[14][15] = P[14][15];
1088  nextP[15][15] = P[15][15];
1089 
1090  if (stateIndexLim > 15) {
1091  nextP[0][16] = P[0][16]*SPP[5] - P[1][16]*SPP[4] + P[2][16]*SPP[8] + P[9][16]*SPP[22] + P[12][16]*SPP[18];
1092  nextP[1][16] = P[1][16]*SPP[6] - P[0][16]*SPP[2] - P[2][16]*SPP[9] + P[10][16]*SPP[22] + P[13][16]*SPP[17];
1093  nextP[2][16] = P[0][16]*SPP[14] - P[1][16]*SPP[3] + P[2][16]*SPP[13] + P[11][16]*SPP[22] + P[14][16]*SPP[16];
1094  nextP[3][16] = P[3][16] + P[0][16]*SPP[1] + P[1][16]*SPP[19] + P[2][16]*SPP[15] - P[15][16]*SPP[21];
1095  nextP[4][16] = P[4][16] + P[15][16]*SF[22] + P[0][16]*SPP[20] + P[1][16]*SPP[12] + P[2][16]*SPP[11];
1096  nextP[5][16] = P[5][16] + P[15][16]*SF[20] - P[0][16]*SPP[7] + P[1][16]*SPP[10] + P[2][16]*SPP[0];
1097  nextP[6][16] = P[6][16] + P[3][16]*dt;
1098  nextP[7][16] = P[7][16] + P[4][16]*dt;
1099  nextP[8][16] = P[8][16] + P[5][16]*dt;
1100  nextP[9][16] = P[9][16];
1101  nextP[10][16] = P[10][16];
1102  nextP[11][16] = P[11][16];
1103  nextP[12][16] = P[12][16];
1104  nextP[13][16] = P[13][16];
1105  nextP[14][16] = P[14][16];
1106  nextP[15][16] = P[15][16];
1107  nextP[16][16] = P[16][16];
1108  nextP[0][17] = P[0][17]*SPP[5] - P[1][17]*SPP[4] + P[2][17]*SPP[8] + P[9][17]*SPP[22] + P[12][17]*SPP[18];
1109  nextP[1][17] = P[1][17]*SPP[6] - P[0][17]*SPP[2] - P[2][17]*SPP[9] + P[10][17]*SPP[22] + P[13][17]*SPP[17];
1110  nextP[2][17] = P[0][17]*SPP[14] - P[1][17]*SPP[3] + P[2][17]*SPP[13] + P[11][17]*SPP[22] + P[14][17]*SPP[16];
1111  nextP[3][17] = P[3][17] + P[0][17]*SPP[1] + P[1][17]*SPP[19] + P[2][17]*SPP[15] - P[15][17]*SPP[21];
1112  nextP[4][17] = P[4][17] + P[15][17]*SF[22] + P[0][17]*SPP[20] + P[1][17]*SPP[12] + P[2][17]*SPP[11];
1113  nextP[5][17] = P[5][17] + P[15][17]*SF[20] - P[0][17]*SPP[7] + P[1][17]*SPP[10] + P[2][17]*SPP[0];
1114  nextP[6][17] = P[6][17] + P[3][17]*dt;
1115  nextP[7][17] = P[7][17] + P[4][17]*dt;
1116  nextP[8][17] = P[8][17] + P[5][17]*dt;
1117  nextP[9][17] = P[9][17];
1118  nextP[10][17] = P[10][17];
1119  nextP[11][17] = P[11][17];
1120  nextP[12][17] = P[12][17];
1121  nextP[13][17] = P[13][17];
1122  nextP[14][17] = P[14][17];
1123  nextP[15][17] = P[15][17];
1124  nextP[16][17] = P[16][17];
1125  nextP[17][17] = P[17][17];
1126  nextP[0][18] = P[0][18]*SPP[5] - P[1][18]*SPP[4] + P[2][18]*SPP[8] + P[9][18]*SPP[22] + P[12][18]*SPP[18];
1127  nextP[1][18] = P[1][18]*SPP[6] - P[0][18]*SPP[2] - P[2][18]*SPP[9] + P[10][18]*SPP[22] + P[13][18]*SPP[17];
1128  nextP[2][18] = P[0][18]*SPP[14] - P[1][18]*SPP[3] + P[2][18]*SPP[13] + P[11][18]*SPP[22] + P[14][18]*SPP[16];
1129  nextP[3][18] = P[3][18] + P[0][18]*SPP[1] + P[1][18]*SPP[19] + P[2][18]*SPP[15] - P[15][18]*SPP[21];
1130  nextP[4][18] = P[4][18] + P[15][18]*SF[22] + P[0][18]*SPP[20] + P[1][18]*SPP[12] + P[2][18]*SPP[11];
1131  nextP[5][18] = P[5][18] + P[15][18]*SF[20] - P[0][18]*SPP[7] + P[1][18]*SPP[10] + P[2][18]*SPP[0];
1132  nextP[6][18] = P[6][18] + P[3][18]*dt;
1133  nextP[7][18] = P[7][18] + P[4][18]*dt;
1134  nextP[8][18] = P[8][18] + P[5][18]*dt;
1135  nextP[9][18] = P[9][18];
1136  nextP[10][18] = P[10][18];
1137  nextP[11][18] = P[11][18];
1138  nextP[12][18] = P[12][18];
1139  nextP[13][18] = P[13][18];
1140  nextP[14][18] = P[14][18];
1141  nextP[15][18] = P[15][18];
1142  nextP[16][18] = P[16][18];
1143  nextP[17][18] = P[17][18];
1144  nextP[18][18] = P[18][18];
1145  nextP[0][19] = P[0][19]*SPP[5] - P[1][19]*SPP[4] + P[2][19]*SPP[8] + P[9][19]*SPP[22] + P[12][19]*SPP[18];
1146  nextP[1][19] = P[1][19]*SPP[6] - P[0][19]*SPP[2] - P[2][19]*SPP[9] + P[10][19]*SPP[22] + P[13][19]*SPP[17];
1147  nextP[2][19] = P[0][19]*SPP[14] - P[1][19]*SPP[3] + P[2][19]*SPP[13] + P[11][19]*SPP[22] + P[14][19]*SPP[16];
1148  nextP[3][19] = P[3][19] + P[0][19]*SPP[1] + P[1][19]*SPP[19] + P[2][19]*SPP[15] - P[15][19]*SPP[21];
1149  nextP[4][19] = P[4][19] + P[15][19]*SF[22] + P[0][19]*SPP[20] + P[1][19]*SPP[12] + P[2][19]*SPP[11];
1150  nextP[5][19] = P[5][19] + P[15][19]*SF[20] - P[0][19]*SPP[7] + P[1][19]*SPP[10] + P[2][19]*SPP[0];
1151  nextP[6][19] = P[6][19] + P[3][19]*dt;
1152  nextP[7][19] = P[7][19] + P[4][19]*dt;
1153  nextP[8][19] = P[8][19] + P[5][19]*dt;
1154  nextP[9][19] = P[9][19];
1155  nextP[10][19] = P[10][19];
1156  nextP[11][19] = P[11][19];
1157  nextP[12][19] = P[12][19];
1158  nextP[13][19] = P[13][19];
1159  nextP[14][19] = P[14][19];
1160  nextP[15][19] = P[15][19];
1161  nextP[16][19] = P[16][19];
1162  nextP[17][19] = P[17][19];
1163  nextP[18][19] = P[18][19];
1164  nextP[19][19] = P[19][19];
1165  nextP[0][20] = P[0][20]*SPP[5] - P[1][20]*SPP[4] + P[2][20]*SPP[8] + P[9][20]*SPP[22] + P[12][20]*SPP[18];
1166  nextP[1][20] = P[1][20]*SPP[6] - P[0][20]*SPP[2] - P[2][20]*SPP[9] + P[10][20]*SPP[22] + P[13][20]*SPP[17];
1167  nextP[2][20] = P[0][20]*SPP[14] - P[1][20]*SPP[3] + P[2][20]*SPP[13] + P[11][20]*SPP[22] + P[14][20]*SPP[16];
1168  nextP[3][20] = P[3][20] + P[0][20]*SPP[1] + P[1][20]*SPP[19] + P[2][20]*SPP[15] - P[15][20]*SPP[21];
1169  nextP[4][20] = P[4][20] + P[15][20]*SF[22] + P[0][20]*SPP[20] + P[1][20]*SPP[12] + P[2][20]*SPP[11];
1170  nextP[5][20] = P[5][20] + P[15][20]*SF[20] - P[0][20]*SPP[7] + P[1][20]*SPP[10] + P[2][20]*SPP[0];
1171  nextP[6][20] = P[6][20] + P[3][20]*dt;
1172  nextP[7][20] = P[7][20] + P[4][20]*dt;
1173  nextP[8][20] = P[8][20] + P[5][20]*dt;
1174  nextP[9][20] = P[9][20];
1175  nextP[10][20] = P[10][20];
1176  nextP[11][20] = P[11][20];
1177  nextP[12][20] = P[12][20];
1178  nextP[13][20] = P[13][20];
1179  nextP[14][20] = P[14][20];
1180  nextP[15][20] = P[15][20];
1181  nextP[16][20] = P[16][20];
1182  nextP[17][20] = P[17][20];
1183  nextP[18][20] = P[18][20];
1184  nextP[19][20] = P[19][20];
1185  nextP[20][20] = P[20][20];
1186  nextP[0][21] = P[0][21]*SPP[5] - P[1][21]*SPP[4] + P[2][21]*SPP[8] + P[9][21]*SPP[22] + P[12][21]*SPP[18];
1187  nextP[1][21] = P[1][21]*SPP[6] - P[0][21]*SPP[2] - P[2][21]*SPP[9] + P[10][21]*SPP[22] + P[13][21]*SPP[17];
1188  nextP[2][21] = P[0][21]*SPP[14] - P[1][21]*SPP[3] + P[2][21]*SPP[13] + P[11][21]*SPP[22] + P[14][21]*SPP[16];
1189  nextP[3][21] = P[3][21] + P[0][21]*SPP[1] + P[1][21]*SPP[19] + P[2][21]*SPP[15] - P[15][21]*SPP[21];
1190  nextP[4][21] = P[4][21] + P[15][21]*SF[22] + P[0][21]*SPP[20] + P[1][21]*SPP[12] + P[2][21]*SPP[11];
1191  nextP[5][21] = P[5][21] + P[15][21]*SF[20] - P[0][21]*SPP[7] + P[1][21]*SPP[10] + P[2][21]*SPP[0];
1192  nextP[6][21] = P[6][21] + P[3][21]*dt;
1193  nextP[7][21] = P[7][21] + P[4][21]*dt;
1194  nextP[8][21] = P[8][21] + P[5][21]*dt;
1195  nextP[9][21] = P[9][21];
1196  nextP[10][21] = P[10][21];
1197  nextP[11][21] = P[11][21];
1198  nextP[12][21] = P[12][21];
1199  nextP[13][21] = P[13][21];
1200  nextP[14][21] = P[14][21];
1201  nextP[15][21] = P[15][21];
1202  nextP[16][21] = P[16][21];
1203  nextP[17][21] = P[17][21];
1204  nextP[18][21] = P[18][21];
1205  nextP[19][21] = P[19][21];
1206  nextP[20][21] = P[20][21];
1207  nextP[21][21] = P[21][21];
1208 
1209  if (stateIndexLim > 21) {
1210  nextP[0][22] = P[0][22]*SPP[5] - P[1][22]*SPP[4] + P[2][22]*SPP[8] + P[9][22]*SPP[22] + P[12][22]*SPP[18];
1211  nextP[1][22] = P[1][22]*SPP[6] - P[0][22]*SPP[2] - P[2][22]*SPP[9] + P[10][22]*SPP[22] + P[13][22]*SPP[17];
1212  nextP[2][22] = P[0][22]*SPP[14] - P[1][22]*SPP[3] + P[2][22]*SPP[13] + P[11][22]*SPP[22] + P[14][22]*SPP[16];
1213  nextP[3][22] = P[3][22] + P[0][22]*SPP[1] + P[1][22]*SPP[19] + P[2][22]*SPP[15] - P[15][22]*SPP[21];
1214  nextP[4][22] = P[4][22] + P[15][22]*SF[22] + P[0][22]*SPP[20] + P[1][22]*SPP[12] + P[2][22]*SPP[11];
1215  nextP[5][22] = P[5][22] + P[15][22]*SF[20] - P[0][22]*SPP[7] + P[1][22]*SPP[10] + P[2][22]*SPP[0];
1216  nextP[6][22] = P[6][22] + P[3][22]*dt;
1217  nextP[7][22] = P[7][22] + P[4][22]*dt;
1218  nextP[8][22] = P[8][22] + P[5][22]*dt;
1219  nextP[9][22] = P[9][22];
1220  nextP[10][22] = P[10][22];
1221  nextP[11][22] = P[11][22];
1222  nextP[12][22] = P[12][22];
1223  nextP[13][22] = P[13][22];
1224  nextP[14][22] = P[14][22];
1225  nextP[15][22] = P[15][22];
1226  nextP[16][22] = P[16][22];
1227  nextP[17][22] = P[17][22];
1228  nextP[18][22] = P[18][22];
1229  nextP[19][22] = P[19][22];
1230  nextP[20][22] = P[20][22];
1231  nextP[21][22] = P[21][22];
1232  nextP[22][22] = P[22][22];
1233  nextP[0][23] = P[0][23]*SPP[5] - P[1][23]*SPP[4] + P[2][23]*SPP[8] + P[9][23]*SPP[22] + P[12][23]*SPP[18];
1234  nextP[1][23] = P[1][23]*SPP[6] - P[0][23]*SPP[2] - P[2][23]*SPP[9] + P[10][23]*SPP[22] + P[13][23]*SPP[17];
1235  nextP[2][23] = P[0][23]*SPP[14] - P[1][23]*SPP[3] + P[2][23]*SPP[13] + P[11][23]*SPP[22] + P[14][23]*SPP[16];
1236  nextP[3][23] = P[3][23] + P[0][23]*SPP[1] + P[1][23]*SPP[19] + P[2][23]*SPP[15] - P[15][23]*SPP[21];
1237  nextP[4][23] = P[4][23] + P[15][23]*SF[22] + P[0][23]*SPP[20] + P[1][23]*SPP[12] + P[2][23]*SPP[11];
1238  nextP[5][23] = P[5][23] + P[15][23]*SF[20] - P[0][23]*SPP[7] + P[1][23]*SPP[10] + P[2][23]*SPP[0];
1239  nextP[6][23] = P[6][23] + P[3][23]*dt;
1240  nextP[7][23] = P[7][23] + P[4][23]*dt;
1241  nextP[8][23] = P[8][23] + P[5][23]*dt;
1242  nextP[9][23] = P[9][23];
1243  nextP[10][23] = P[10][23];
1244  nextP[11][23] = P[11][23];
1245  nextP[12][23] = P[12][23];
1246  nextP[13][23] = P[13][23];
1247  nextP[14][23] = P[14][23];
1248  nextP[15][23] = P[15][23];
1249  nextP[16][23] = P[16][23];
1250  nextP[17][23] = P[17][23];
1251  nextP[18][23] = P[18][23];
1252  nextP[19][23] = P[19][23];
1253  nextP[20][23] = P[20][23];
1254  nextP[21][23] = P[21][23];
1255  nextP[22][23] = P[22][23];
1256  nextP[23][23] = P[23][23];
1257  }
1258  }
1259 
1260  // Copy upper diagonal to lower diagonal taking advantage of symmetry
1261  for (uint8_t colIndex=0; colIndex<=stateIndexLim; colIndex++)
1262  {
1263  for (uint8_t rowIndex=0; rowIndex<colIndex; rowIndex++)
1264  {
1265  nextP[colIndex][rowIndex] = nextP[rowIndex][colIndex];
1266  }
1267  }
1268 
1269  // add the general state process noise variances
1270  for (uint8_t i=0; i<=stateIndexLim; i++)
1271  {
1272  nextP[i][i] = nextP[i][i] + processNoise[i];
1273  }
1274 
1275  // if the total position variance exceeds 1e4 (100m), then stop covariance
1276  // growth by setting the predicted to the previous values
1277  // This prevent an ill conditioned matrix from occurring for long periods
1278  // without GPS
1279  if ((P[6][6] + P[7][7]) > 1e4f)
1280  {
1281  for (uint8_t i=6; i<=7; i++)
1282  {
1283  for (uint8_t j=0; j<=stateIndexLim; j++)
1284  {
1285  nextP[i][j] = P[i][j];
1286  nextP[j][i] = P[j][i];
1287  }
1288  }
1289  }
1290 
1291  // copy covariances to output
1292  CopyCovariances();
1293 
1294  // constrain diagonals to prevent ill-conditioning
1296 
1298 }
1299 
1300 // zero specified range of rows in the state covariance matrix
1301 void NavEKF2_core::zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
1302 {
1303  uint8_t row;
1304  for (row=first; row<=last; row++)
1305  {
1306  memset(&covMat[row][0], 0, sizeof(covMat[0][0])*24);
1307  }
1308 }
1309 
1310 // zero specified range of columns in the state covariance matrix
1311 void NavEKF2_core::zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
1312 {
1313  uint8_t row;
1314  for (row=0; row<=23; row++)
1315  {
1316  memset(&covMat[row][first], 0, sizeof(covMat[0][0])*(1+last-first));
1317  }
1318 }
1319 
1320 // reset the output data to the current EKF state
1322 {
1326  // write current measurement to entire table
1327  for (uint8_t i=0; i<imu_buffer_length; i++) {
1329  }
1331  // reset the states for the complementary filter used to provide a vertical position dervative output
1334 }
1335 
1336 // Reset the stored output quaternion history to current EKF state
1338 {
1340  // write current measurement to entire table
1341  for (uint8_t i=0; i<imu_buffer_length; i++) {
1342  storedOutput[i].quat = outputDataNew.quat;
1343  }
1345 }
1346 
1347 // Rotate the stored output quaternion history through a quaternion rotation
1349 {
1350  outputDataNew.quat = outputDataNew.quat*deltaQuat;
1351  // write current measurement to entire table
1352  for (uint8_t i=0; i<imu_buffer_length; i++) {
1353  storedOutput[i].quat = storedOutput[i].quat*deltaQuat;
1354  }
1356 }
1357 
1358 // calculate nav to body quaternions from body to nav rotation matrix
1359 void NavEKF2_core::quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
1360 {
1361  // Calculate the body to nav cosine matrix
1362  quat.rotation_matrix(Tbn);
1363 }
1364 
1365 // force symmetry on the covariance matrix to prevent ill-conditioning
1367 {
1368  for (uint8_t i=1; i<=stateIndexLim; i++)
1369  {
1370  for (uint8_t j=0; j<=i-1; j++)
1371  {
1372  float temp = 0.5f*(P[i][j] + P[j][i]);
1373  P[i][j] = temp;
1374  P[j][i] = temp;
1375  }
1376  }
1377 }
1378 
1379 // copy covariances across from covariance prediction calculation
1381 {
1382  // copy predicted covariances
1383  for (uint8_t i=0; i<=stateIndexLim; i++) {
1384  for (uint8_t j=0; j<=stateIndexLim; j++)
1385  {
1386  P[i][j] = nextP[i][j];
1387  }
1388  }
1389 }
1390 
1391 // constrain variances (diagonal terms) in the state covariance matrix to prevent ill-conditioning
1393 {
1394  for (uint8_t i=0; i<=2; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0f); // attitude error
1395  for (uint8_t i=3; i<=5; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0e3f); // velocities
1396  for (uint8_t i=6; i<=7; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0e6f);
1397  P[8][8] = constrain_float(P[8][8],0.0f,1.0e6f); // vertical position
1398  for (uint8_t i=9; i<=11; i++) P[i][i] = constrain_float(P[i][i],0.0f,sq(0.175f * dtEkfAvg)); // delta angle biases
1399  if (PV_AidingMode != AID_NONE) {
1400  for (uint8_t i=12; i<=14; i++) P[i][i] = constrain_float(P[i][i],0.0f,0.01f); // delta angle scale factors
1401  } else {
1402  // we can't reliably estimate scale factors when there is no aiding data due to transient manoeuvre induced innovations
1403  // so inhibit estimation by keeping covariance elements at zero
1404  zeroRows(P,12,14);
1405  zeroCols(P,12,14);
1406  }
1407  P[15][15] = constrain_float(P[15][15],0.0f,sq(10.0f * dtEkfAvg)); // delta velocity bias
1408  for (uint8_t i=16; i<=18; i++) P[i][i] = constrain_float(P[i][i],0.0f,0.01f); // earth magnetic field
1409  for (uint8_t i=19; i<=21; i++) P[i][i] = constrain_float(P[i][i],0.0f,0.01f); // body magnetic field
1410  for (uint8_t i=22; i<=23; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0e3f); // wind velocity
1411 }
1412 
1413 // constrain states to prevent ill-conditioning
1415 {
1416  // attitude errors are limited between +-1
1417  for (uint8_t i=0; i<=2; i++) statesArray[i] = constrain_float(statesArray[i],-1.0f,1.0f);
1418  // velocity limit 500 m/sec (could set this based on some multiple of max airspeed * EAS2TAS)
1419  for (uint8_t i=3; i<=5; i++) statesArray[i] = constrain_float(statesArray[i],-5.0e2f,5.0e2f);
1420  // position limit 1000 km - TODO apply circular limit
1421  for (uint8_t i=6; i<=7; i++) statesArray[i] = constrain_float(statesArray[i],-1.0e6f,1.0e6f);
1422  // height limit covers home alt on everest through to home alt at SL and ballon drop
1424  // gyro bias limit (this needs to be set based on manufacturers specs)
1425  for (uint8_t i=9; i<=11; i++) statesArray[i] = constrain_float(statesArray[i],-GYRO_BIAS_LIMIT*dtEkfAvg,GYRO_BIAS_LIMIT*dtEkfAvg);
1426  // gyro scale factor limit of +-5% (this needs to be set based on manufacturers specs)
1427  for (uint8_t i=12; i<=14; i++) statesArray[i] = constrain_float(statesArray[i],0.95f,1.05f);
1428  // Z accel bias limit 1.0 m/s^2 (this needs to be finalised from test data)
1429  stateStruct.accel_zbias = constrain_float(stateStruct.accel_zbias,-1.0f*dtEkfAvg,1.0f*dtEkfAvg);
1430  // earth magnetic field limit
1431  for (uint8_t i=16; i<=18; i++) statesArray[i] = constrain_float(statesArray[i],-1.0f,1.0f);
1432  // body magnetic field limit
1433  for (uint8_t i=19; i<=21; i++) statesArray[i] = constrain_float(statesArray[i],-0.5f,0.5f);
1434  // wind velocity limit 100 m/s (could be based on some multiple of max airspeed * EAS2TAS) - TODO apply circular limit
1435  for (uint8_t i=22; i<=23; i++) statesArray[i] = constrain_float(statesArray[i],-100.0f,100.0f);
1436  // constrain the terrain state to be below the vehicle height unless we are using terrain as the height datum
1437  if (!inhibitGndState) {
1439  }
1440 }
1441 
1442 // calculate the NED earth spin vector in rad/sec
1443 void NavEKF2_core::calcEarthRateNED(Vector3f &omega, int32_t latitude) const
1444 {
1445  float lat_rad = radians(latitude*1.0e-7f);
1446  omega.x = earthRate*cosf(lat_rad);
1447  omega.y = 0;
1448  omega.z = -earthRate*sinf(lat_rad);
1449 }
1450 
1451 // initialise the earth magnetic field states using declination, suppled roll/pitch
1452 // and magnetometer measurements and return initial attitude quaternion
1454 {
1455  // declare local variables required to calculate initial orientation and magnetic field
1456  float yaw;
1457  Matrix3f Tbn;
1458  Vector3f initMagNED;
1459  Quaternion initQuat;
1460 
1461  if (use_compass()) {
1462  // calculate rotation matrix from body to NED frame
1463  Tbn.from_euler(roll, pitch, 0.0f);
1464 
1465  // read the magnetometer data
1466  readMagData();
1467 
1468  // rotate the magnetic field into NED axes
1469  initMagNED = Tbn * magDataDelayed.mag;
1470 
1471  // calculate heading of mag field rel to body heading
1472  float magHeading = atan2f(initMagNED.y, initMagNED.x);
1473 
1474  // get the magnetic declination
1475  float magDecAng = use_compass() ? _ahrs->get_compass()->get_declination() : 0;
1476 
1477  // calculate yaw angle rel to true north
1478  yaw = magDecAng - magHeading;
1479 
1480  // calculate initial filter quaternion states using yaw from magnetometer
1481  // store the yaw change so that it can be retrieved externally for use by the control loops to prevent yaw disturbances following a reset
1482  Vector3f tempEuler;
1483  stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
1484  // this check ensures we accumulate the resets that occur within a single iteration of the EKF
1486  yawResetAngle = 0.0f;
1487  }
1488  yawResetAngle += wrap_PI(yaw - tempEuler.z);
1490  // calculate an initial quaternion using the new yaw value
1491  initQuat.from_euler(roll, pitch, yaw);
1492  // zero the attitude covariances becasue the corelations will now be invalid
1493  zeroAttCovOnly();
1494 
1495  // calculate initial Tbn matrix and rotate Mag measurements into NED
1496  // to set initial NED magnetic field states
1497  // don't do this if the earth field has already been learned
1498  if (!magFieldLearned) {
1499  initQuat.rotation_matrix(Tbn);
1501 
1502  // set the NE earth magnetic field states using the published declination
1503  // and set the corresponding variances and covariances
1505 
1506  // set the remaining variances and covariances
1507  zeroRows(P,18,21);
1508  zeroCols(P,18,21);
1509  P[18][18] = sq(frontend->_magNoise);
1510  P[19][19] = P[18][18];
1511  P[20][20] = P[18][18];
1512  P[21][21] = P[18][18];
1513 
1514  }
1515 
1516  // record the fact we have initialised the magnetic field states
1517  recordMagReset();
1518 
1519  // clear mag state reset request
1520  magStateResetRequest = false;
1521 
1522  } else {
1523  // this function should not be called if there is no compass data but if is is, return the
1524  // current attitude
1525  initQuat = stateStruct.quat;
1526  }
1527 
1528  // return attitude quaternion
1529  return initQuat;
1530 }
1531 
1532 // zero the attitude covariances, but preserve the variances
1534 {
1535  float varTemp[3];
1536  for (uint8_t index=0; index<=2; index++) {
1537  varTemp[index] = P[index][index];
1538  }
1539  zeroCols(P,0,2);
1540  zeroRows(P,0,2);
1541  for (uint8_t index=0; index<=2; index++) {
1542  P[index][index] = varTemp[index];
1543  }
1544 }
1545 
1546 #endif // HAL_CPU_CLASS
uint32_t lastVelReset_ms
Vector2f posResetNE
uint8_t rngMeasIndex[2]
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
uint32_t lastVelPassTime_ms
AP_Float _gpsVertVelNoise
Definition: AP_NavEKF2.h:352
#define EKF_TARGET_DT
void correctDeltaAngle(Vector3f &delAng, float delAngDT)
struct Location gpsloc_prev
uint32_t lastBaroReceived_ms
obs_ring_buffer_t< gps_elements > storedGPS
uint32_t extNavMeasTime_ms
Vector3f earthRateNED
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
Quaternion quatAtLastMagReset
Vector3f accelPosOffset
AP_Float _magNoise
Definition: AP_NavEKF2.h:355
imu_ring_buffer_t< output_elements > storedOutput
bool posVelFusionDelayed
bool extNavYawResetRequest
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
Definition: Util.h:102
float get_declination() const
char prearm_fail_string[40]
uint32_t prevTasStep_ms
uint32_t lastPosReset_ms
void InitialiseVariables()
void UpdateStrapdownEquationsNED()
Vector3f posErrintegral
uint8_t magStoreIndex
mag_elements magDataDelayed
output_elements outputDataNew
NavEKF2 * frontend
uint64_t imuSampleTime_us
Definition: AP_NavEKF2.h:437
bool assume_zero_sideslip(void) const
Vector28 statesArray
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
Vector3f velDotNEDfilt
const AP_AHRS * _ahrs
AP_Float _gpsHorizVelNoise
Definition: AP_NavEKF2.h:351
float yawInnovAtLastMagReset
obs_ring_buffer_t< range_elements > storedRange
uint32_t lastRngMeasTime_ms
ext_nav_elements extNavDataNew
AP_Float _gyroBiasProcessNoise
Definition: AP_NavEKF2.h:363
struct NavEKF2_core::@147 mag_state
uint8_t gpsStoreIndex
AP_Float _gyrNoise
Definition: AP_NavEKF2.h:361
Vector2f flowGyroBias
AP_HAL::Util * util
Definition: HAL.h:115
Vector3f delAngBodyOF
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
void CovariancePrediction()
uint8_t core_index
float beaconVehiclePosErr
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
float hgtInnovFiltState
float OffsetMinInnovFilt
uint32_t magYawResetTimer_ms
void updateFilterStatus(void)
float storedRngMeas[2][3]
uint32_t lastDecayTime_ms
Vector3f rngBcnPosSum
bool setup_core(NavEKF2 *_frontend, uint8_t _imu_index, uint8_t _core_index)
bool optFlowFusionDelayed
uint32_t lastHgtPassTime_ms
bool rngBcnAlignmentStarted
uint32_t lastTimeGpsReceived_ms
Quaternion calcQuatAndFieldStates(float roll, float pitch)
struct NavEKF2_core::state_elements & stateStruct
uint32_t timeAtLastAuxEKF_ms
uint32_t lastGpsVelFail_ms
uint32_t touchdownExpectedSet_ms
uint32_t takeoffExpectedSet_ms
uint32_t imuSampleTime_ms
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
output_elements outputDataDelayed
bool InitialiseFilterBootstrap(void)
Vector2f heldVelNE
obs_ring_buffer_t< tas_elements > storedTAS
uint32_t lastInnovFailTime_ms
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
uint32_t lastInnovPassTime_ms
void quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
uint8_t get_primary(void) const
Definition: AP_Compass.h:277
const Compass * get_compass() const
Definition: AP_AHRS.h:150
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
imu_elements imuDataDelayed
AP_Float _baroAltNoise
Definition: AP_NavEKF2.h:354
uint32_t lastPreAlignGpsCheckTime_ms
const Vector3f & get_accel(uint8_t i) const
uint32_t framesSincePredict
T y
Definition: vector2.h:37
float bcnPosOffsetMaxVar
float receiverPosCov[3][3]
uint8_t lastBeaconIndex
AP_Float _gyroScaleProcessNoise
Definition: AP_NavEKF2.h:381
Vector3f delVelCorrected
uint32_t secondLastGpsTime_ms
struct NavEKF2_core::@145 faultStatus
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
AP_Float _magEarthProcessNoise
Definition: AP_NavEKF2.h:359
uint8_t rngBcnFuseDataReportIndex
uint8_t rngBcnStoreIndex
#define GRAVITY_MSS
Definition: definitions.h:47
bool startPredictEnabled
uint8_t magSelectIndex
#define f(i)
uint32_t lastHealthyMagTime_ms
float bcnPosOffsetMinVar
uint32_t prevFlowFuseTime_ms
uint32_t prevBetaStep_ms
Vector3f velOffsetNED
T y
Definition: vector3.h:67
struct NavEKF2_core::@146 gpsCheckStatus
uint8_t rangeStoreIndex
AP_Float _gpsHorizPosNoise
Definition: AP_NavEKF2.h:353
float innovationIncrement
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
T z
Definition: vector3.h:67
float sAccFilterState2
AP_Float _accelBiasProcessNoise
Definition: AP_NavEKF2.h:364
AidingMode PV_AidingModePrev
float posDownAtLastMagReset
AP_Float _magBodyProcessNoise
Definition: AP_NavEKF2.h:360
uint8_t activeHgtSource
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
uint32_t gndHgtValidTime_ms
uint32_t rngBcnLast3DmeasTime_ms
Vector3f velErrintegral
static const uint32_t OBS_BUFFER_LENGTH
AP_Float _wndVarHgtRateScale
Definition: AP_NavEKF2.h:358
obs_ring_buffer_t< mag_elements > storedMag
void from_axis_angle(Vector3f v)
Definition: quaternion.cpp:154
uint8_t tasStoreIndex
Vector3f beaconVehiclePosNED
void normalize()
Definition: vector3.h:176
float posDownDerivative
uint32_t lastMagUpdate_us
AP_Float _accNoise
Definition: AP_NavEKF2.h:362
Matrix3f prevTnb
bool use_compass(void) const
AP_HAL::Util::perf_counter_t _perf_test[10]
void UpdateFilter(bool predict)
uint8_t ofStoreIndex
float length(void) const
Definition: vector3.cpp:288
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
obs_ring_buffer_t< rng_bcn_elements > storedRangeBeacon
bool magStateInitComplete
void zero(void)
Definition: matrix3.cpp:238
bool sideSlipFusionDelayed
Vector3f delAngCorrected
AP_HAL::Util::perf_counter_t _perf_UpdateFilter
void StoreQuatReset(void)
obs_ring_buffer_t< baro_elements > storedBaro
AP_Float _windVelProcessNoise
Definition: AP_NavEKF2.h:357
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
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
uint32_t lastGpsAidBadTime_ms
#define INIT_ACCEL_BIAS_UNCERTAINTY
nav_filter_status filterStatus
ext_nav_elements extNavDataDelayed
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
float sAccFilterState1
Vector3f velDotNED
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
uint32_t lastRngBcnPassTime_ms
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void zero()
Definition: vector2.h:125
uint8_t last_gps_idx
rng_bcn_elements rngBcnDataDelayed
Vector24 processNoise
uint32_t flowMeaTime_ms
Vector3f delAngCorrection
Vector3f posOffsetNED
#define earthRate
uint8_t stateIndexLim
imu_ring_buffer_t< imu_elements > storedIMU
Vector2f velResetNE
float sq(const T val)
Definition: AP_Math.h:170
uint32_t lastTimeRngBcn_ms[10]
Vector3f outputTrackError
#define GYRO_BIAS_LIMIT
Quaternion inverse(void) const
Definition: quaternion.cpp:292
bool is_zero(void) const
Definition: vector3.h:159
obs_ring_buffer_t< ext_nav_elements > storedExtNav
bool expectGndEffectTouchdown
bool airSpdFusionDelayed
bool rngBcnAlignmentCompleted
uint8_t localFilterTimeStep_ms
AP_InertialSensor & ins()
void rotate(const Vector3f &v)
Definition: quaternion.cpp:182
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
const AP_AHRS * _ahrs
Definition: AP_NavEKF2.h:343
uint8_t lastRngBcnChecked
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool lastMagOffsetsValid
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
bool expectGndEffectTakeoff
uint32_t timeTasReceived_ms
uint32_t ekfStartTime_ms
float OffsetMaxInnovFilt
uint32_t lastPosPassTime_ms
uint32_t lastTasPassTime_ms
uint8_t baroStoreIndex
uint32_t extNavLastPosResetTime_ms
uint32_t rngValidMeaTime_ms
void StoreOutputReset(void)
AP_HAL::Util::perf_counter_t _perf_CovariancePrediction
float get_loop_delta_t(void) const
void correctDeltaVelocity(Vector3f &delVel, float delVelDT)
uint32_t terrainHgtStableSet_ms
ftype Matrix24[24][24]
float InitialGyroBiasUncertainty(void) const
uint32_t storedRngMeasTime_ms[2][3]
uint32_t flowValidMeaTime_ms
rng_bcn_elements rngBcnDataNew
struct NavEKF2_core::@144 rngBcnFusionReport[10]
uint8_t imu_buffer_length
Vector3f receiverPos
uint32_t lastYawReset_ms
Vector2f lastKnownPositionNE
obs_ring_buffer_t< of_elements > storedOF
imu_elements imuDataNew
void zero()
Definition: vector3.h:182
bool allMagSensorsFailed
AidingMode PV_AidingMode
T x
Definition: vector3.h:67
AP_Int8 _tauVelPosOutput
Definition: AP_NavEKF2.h:390
uint32_t lastPosResetD_ms
uint32_t lastYawTime_ms
imu_elements imuDataDownSampledNew
uint32_t lastGpsCheckTime_ms
void StoreQuatRotate(Quaternion deltaQuat)