APM:Libraries
AP_NavEKF2_core.h
Go to the documentation of this file.
1 /*
2  24 state EKF based on the derivation in https://github.com/priseborough/
3  InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/
4  GenerateNavFilterEquations.m
5 
6  Converted from Matlab to C++ by Paul Riseborough
7 
8  This program is free software: you can redistribute it and/or modify
9  it under the terms of the GNU General Public License as published by
10  the Free Software Foundation, either version 3 of the License, or
11  (at your option) any later version.
12 
13  This program is distributed in the hope that it will be useful,
14  but WITHOUT ANY WARRANTY; without even the implied warranty of
15  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  GNU General Public License for more details.
17 
18  You should have received a copy of the GNU General Public License
19  along with this program. If not, see <http://www.gnu.org/licenses/>.
20  */
21 #pragma once
22 
23 #pragma GCC optimize("O3")
24 
25 #define EK2_DISABLE_INTERRUPTS 0
26 
27 
28 #include <AP_Math/AP_Math.h>
29 #include "AP_NavEKF2.h"
30 #include <stdio.h>
31 #include <AP_Math/vectorN.h>
33 
34 // GPS pre-flight check bit locations
35 #define MASK_GPS_NSATS (1<<0)
36 #define MASK_GPS_HDOP (1<<1)
37 #define MASK_GPS_SPD_ERR (1<<2)
38 #define MASK_GPS_POS_ERR (1<<3)
39 #define MASK_GPS_YAW_ERR (1<<4)
40 #define MASK_GPS_POS_DRIFT (1<<5)
41 #define MASK_GPS_VERT_SPD (1<<6)
42 #define MASK_GPS_HORIZ_SPD (1<<7)
43 
44 // active height source
45 #define HGT_SOURCE_BARO 0
46 #define HGT_SOURCE_RNG 1
47 #define HGT_SOURCE_GPS 2
48 #define HGT_SOURCE_BCN 3
49 #define HGT_SOURCE_EV 4
50 
51 // target EKF update time step
52 #define EKF_TARGET_DT 0.01f
53 
54 // mag fusion final reset altitude
55 #define EKF2_MAG_FINAL_RESET_ALT 2.5f
56 
57 class AP_AHRS;
58 
60 {
61 public:
62  // Constructor
63  NavEKF2_core(void);
64 
65  // setup this core backend
66  bool setup_core(NavEKF2 *_frontend, uint8_t _imu_index, uint8_t _core_index);
67 
68  // Initialise the states from accelerometer and magnetometer data (if present)
69  // This method can only be used when the vehicle is static
70  bool InitialiseFilterBootstrap(void);
71 
72  // Update Filter States - this should be called whenever new IMU data is available
73  // The predict flag is set true when a new prediction cycle can be started
74  void UpdateFilter(bool predict);
75 
76  // Check basic filter health metrics and return a consolidated health status
77  bool healthy(void) const;
78 
79  // Return a consolidated error score where higher numbers are less healthy
80  // Intended to be used by the front-end to determine which is the primary EKF
81  float errorScore(void) const;
82 
83  // Write the last calculated NE position relative to the reference point (m).
84  // If a calculated solution is not available, use the best available data and return false
85  // If false returned, do not use for flight control
86  bool getPosNE(Vector2f &posNE) const;
87 
88  // Write the last calculated D position relative to the reference point (m).
89  // If a calculated solution is not available, use the best available data and return false
90  // If false returned, do not use for flight control
91  bool getPosD(float &posD) const;
92 
93  // return NED velocity in m/s
94  void getVelNED(Vector3f &vel) const;
95 
96  // Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s
97  // This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
98  // but will always be kinematically consistent with the z component of the EKF position state
99  float getPosDownDerivative(void) const;
100 
101  // This returns the specific forces in the NED frame
102  void getAccelNED(Vector3f &accelNED) const;
103 
104  // return body axis gyro bias estimates in rad/sec
105  void getGyroBias(Vector3f &gyroBias) const;
106 
107  // return body axis gyro scale factor error as a percentage
108  void getGyroScaleErrorPercentage(Vector3f &gyroScale) const;
109 
110  // return tilt error convergence metric
111  void getTiltError(float &ang) const;
112 
113  // reset body axis gyro bias estimates
114  void resetGyroBias(void);
115 
116  // Resets the baro so that it reads zero at the current height
117  // Resets the EKF height to zero
118  // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
119  // Returns true if the height datum reset has been performed
120  // If using a range finder for height no reset is performed and it returns false
121  bool resetHeightDatum(void);
122 
123  // Commands the EKF to not use GPS.
124  // This command must be sent prior to arming as it will only be actioned when the filter is in static mode
125  // This command is forgotten by the EKF each time it goes back into static mode (eg the vehicle disarms)
126  // Returns 0 if command rejected
127  // Returns 1 if attitude, vertical velocity and vertical position will be provided
128  // Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided
129  uint8_t setInhibitGPS(void);
130 
131  // return the horizontal speed limit in m/s set by optical flow sensor limits
132  // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
133  void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const;
134 
135  // return the Z-accel bias estimate in m/s^2
136  void getAccelZBias(float &zbias) const;
137 
138  // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
139  void getWind(Vector3f &wind) const;
140 
141  // return earth magnetic field estimates in measurement units / 1000
142  void getMagNED(Vector3f &magNED) const;
143 
144  // return body magnetic field estimates in measurement units / 1000
145  void getMagXYZ(Vector3f &magXYZ) const;
146 
147  // return the index for the active magnetometer
148  uint8_t getActiveMag() const;
149 
150  // Return estimated magnetometer offsets
151  // Return true if magnetometer offsets are valid
152  bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;
153 
154  // Return the last calculated latitude, longitude and height in WGS-84
155  // If a calculated location isn't available, return a raw GPS measurement
156  // The status will return true if a calculation or raw measurement is available
157  // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
158  bool getLLH(struct Location &loc) const;
159 
160  // return the latitude and longitude and height used to set the NED origin
161  // All NED positions calculated by the filter are relative to this location
162  // Returns false if the origin has not been set
163  bool getOriginLLH(struct Location &loc) const;
164 
165  // set the latitude and longitude and height used to set the NED origin
166  // All NED positions calculated by the filter will be relative to this location
167  // The origin cannot be set if the filter is in a flight mode (eg vehicle armed)
168  // Returns false if the filter has rejected the attempt to set the origin
169  bool setOriginLLH(const Location &loc);
170 
171  // return estimated height above ground level
172  // return false if ground height is not being estimated.
173  bool getHAGL(float &HAGL) const;
174 
175  // return the Euler roll, pitch and yaw angle in radians
176  void getEulerAngles(Vector3f &eulers) const;
177 
178  // return the transformation matrix from XYZ (body) to NED axes
179  void getRotationBodyToNED(Matrix3f &mat) const;
180 
181  // return the quaternions defining the rotation from NED to XYZ (body) axes
182  void getQuaternion(Quaternion &quat) const;
183 
184  // return the innovations for the NED Pos, NED Vel, XYZ Mag and Vtas measurements
185  void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;
186 
187  // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements
188  void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const;
189 
190  // should we use the compass? This is public so it can be used for
191  // reporting via ahrs.use_compass()
192  bool use_compass(void) const;
193 
194  // write the raw optical flow measurements
195  // rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality
196  // rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes.
197  // rawGyroRates are the sensor rotation rates in rad/sec measured by the sensors internal gyro
198  // The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
199  // msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
200  // posOffset is the XYZ flow sensor position in the body frame in m
201  void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset);
202 
203  // return data for debugging optical flow fusion
204  void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const;
205 
206  /*
207  Returns the following data for debugging range beacon fusion
208  ID : beacon identifier
209  rng : measured range to beacon (m)
210  innov : range innovation (m)
211  innovVar : innovation variance (m^2)
212  testRatio : innovation consistency test ratio
213  beaconPosNED : beacon NED position (m)
214  */
215  bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow);
216 
217  // called by vehicle code to specify that a takeoff is happening
218  // causes the EKF to compensate for expected barometer errors due to ground effect
219  void setTakeoffExpected(bool val);
220 
221  // called by vehicle code to specify that a touchdown is expected to happen
222  // causes the EKF to compensate for expected barometer errors due to ground effect
223  void setTouchdownExpected(bool val);
224 
225  // Set to true if the terrain underneath is stable enough to be used as a height reference
226  // in combination with a range finder. Set to false if the terrain underneath the vehicle
227  // cannot be used as a height reference
228  void setTerrainHgtStable(bool val);
229 
230  /*
231  return the filter fault status as a bitmasked integer
232  0 = quaternions are NaN
233  1 = velocities are NaN
234  2 = badly conditioned X magnetometer fusion
235  3 = badly conditioned Y magnetometer fusion
236  5 = badly conditioned Z magnetometer fusion
237  6 = badly conditioned airspeed fusion
238  7 = badly conditioned synthetic sideslip fusion
239  7 = filter is not initialised
240  */
241  void getFilterFaults(uint16_t &faults) const;
242 
243  /*
244  return filter timeout status as a bitmasked integer
245  0 = position measurement timeout
246  1 = velocity measurement timeout
247  2 = height measurement timeout
248  3 = magnetometer measurement timeout
249  5 = unassigned
250  6 = unassigned
251  7 = unassigned
252  7 = unassigned
253  */
254  void getFilterTimeouts(uint8_t &timeouts) const;
255 
256  /*
257  return filter gps quality check status
258  */
259  void getFilterGpsStatus(nav_gps_status &status) const;
260 
261  /*
262  Return a filter function status that indicates:
263  Which outputs are valid
264  If the filter has detected takeoff
265  If the filter has activated the mode that mitigates against ground effect static pressure errors
266  If GPS data is being used
267  */
268  void getFilterStatus(nav_filter_status &status) const;
269 
270  // send an EKF_STATUS_REPORT message to GCS
271  void send_status_report(mavlink_channel_t chan);
272 
273  // provides the height limit to be observed by the control loops
274  // returns false if no height limiting is required
275  // this is needed to ensure the vehicle does not fly too high when using optical flow navigation
276  bool getHeightControlLimit(float &height) const;
277 
278  // return the amount of yaw angle change due to the last yaw angle reset in radians
279  // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
280  uint32_t getLastYawResetAngle(float &yawAng) const;
281 
282  // return the amount of NE position change due to the last position reset in metres
283  // returns the time of the last reset or 0 if no reset has ever occurred
284  uint32_t getLastPosNorthEastReset(Vector2f &pos) const;
285 
286  // return the amount of D position change due to the last position reset in metres
287  // returns the time of the last reset or 0 if no reset has ever occurred
288  uint32_t getLastPosDownReset(float &posD) const;
289 
290  // return the amount of NE velocity change due to the last velocity reset in metres/sec
291  // returns the time of the last reset or 0 if no reset has ever occurred
292  uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
293 
294  // report any reason for why the backend is refusing to initialise
295  const char *prearm_failure_reason(void) const;
296 
297  // report the number of frames lapsed since the last state prediction
298  // this is used by other instances to level load
299  uint8_t getFramesSincePredict(void) const;
300 
301  // publish output observer angular, velocity and position tracking error
303 
304  // get the IMU index
305  uint8_t getIMUIndex(void) const { return imu_index; }
306 
307  // get timing statistics structure
308  void getTimingStatistics(struct ekf_timing &timing);
309 
310  /*
311  * Write position and quaternion data from an external navigation system
312  *
313  * sensOffset : position of the external navigatoin sensor in body frame (m)
314  * pos : position in the RH navigation frame. Frame is assumed to be NED if frameIsNED is true. (m)
315  * quat : quaternion desribing the the rotation from navigation frame to body frame
316  * posErr : 1-sigma spherical position error (m)
317  * angErr : 1-sigma spherical angle error (rad)
318  * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
319  * resetTime_ms : system time of the last position reset request (mSec)
320  *
321  */
322  void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms);
323 
324 private:
325  // Reference to the global EKF frontend for parameters
327  uint8_t imu_index;
328  uint8_t core_index;
330 
331  typedef float ftype;
332 #if MATH_CHECK_INDEXES
333  typedef VectorN<ftype,2> Vector2;
334  typedef VectorN<ftype,3> Vector3;
335  typedef VectorN<ftype,4> Vector4;
336  typedef VectorN<ftype,5> Vector5;
337  typedef VectorN<ftype,6> Vector6;
338  typedef VectorN<ftype,7> Vector7;
339  typedef VectorN<ftype,8> Vector8;
340  typedef VectorN<ftype,9> Vector9;
341  typedef VectorN<ftype,10> Vector10;
342  typedef VectorN<ftype,11> Vector11;
343  typedef VectorN<ftype,13> Vector13;
344  typedef VectorN<ftype,14> Vector14;
345  typedef VectorN<ftype,15> Vector15;
346  typedef VectorN<ftype,22> Vector22;
347  typedef VectorN<ftype,23> Vector23;
348  typedef VectorN<ftype,24> Vector24;
349  typedef VectorN<ftype,25> Vector25;
350  typedef VectorN<ftype,31> Vector31;
351  typedef VectorN<ftype,28> Vector28;
356 #else
357  typedef ftype Vector2[2];
358  typedef ftype Vector3[3];
359  typedef ftype Vector4[4];
360  typedef ftype Vector5[5];
361  typedef ftype Vector6[6];
362  typedef ftype Vector7[7];
363  typedef ftype Vector8[8];
364  typedef ftype Vector9[9];
365  typedef ftype Vector10[10];
366  typedef ftype Vector11[11];
367  typedef ftype Vector13[13];
368  typedef ftype Vector14[14];
369  typedef ftype Vector15[15];
370  typedef ftype Vector22[22];
371  typedef ftype Vector23[23];
372  typedef ftype Vector24[24];
373  typedef ftype Vector25[25];
374  typedef ftype Vector28[28];
375  typedef ftype Matrix3[3][3];
376  typedef ftype Matrix24[24][24];
377  typedef ftype Matrix34_50[34][50];
378  typedef uint32_t Vector_u32_50[50];
379 #endif
380 
381  const AP_AHRS *_ahrs;
382 
383  // the states are available in two forms, either as a Vector31, or
384  // broken down as individual elements. Both are equivalent (same
385  // memory)
386  Vector28 statesArray;
387  struct state_elements {
388  Vector3f angErr; // 0..2
391  Vector3f gyro_bias; // 9..11
392  Vector3f gyro_scale; // 12..14
393  float accel_zbias; // 15
396  Vector2f wind_vel; // 22..23
397  Quaternion quat; // 24..27
398  } &stateStruct;
399 
401  Quaternion quat; // 0..3
404  };
405 
406  struct imu_elements {
407  Vector3f delAng; // 0..2
408  Vector3f delVel; // 3..5
409  float delAngDT; // 6
410  float delVelDT; // 7
411  uint32_t time_ms; // 8
412  };
413 
414  struct gps_elements {
415  Vector2f pos; // 0..1
416  float hgt; // 2
417  Vector3f vel; // 3..5
418  uint32_t time_ms; // 6
419  uint8_t sensor_idx; // 7..9
420  };
421 
422  struct mag_elements {
423  Vector3f mag; // 0..2
424  uint32_t time_ms; // 3
425  };
426 
427  struct baro_elements {
428  float hgt; // 0
429  uint32_t time_ms; // 1
430  };
431 
432  struct range_elements {
433  float rng; // 0
434  uint32_t time_ms; // 1
435  uint8_t sensor_idx; // 2
436  };
437 
439  float rng; // range measurement to each beacon (m)
440  Vector3f beacon_posNED; // NED position of the beacon (m)
441  float rngErr; // range measurement error 1-std (m)
442  uint8_t beacon_ID; // beacon identification number
443  uint32_t time_ms; // measurement timestamp (msec)
444  };
445 
446  struct tas_elements {
447  float tas; // 0
448  uint32_t time_ms; // 1
449  };
450 
451  struct of_elements {
454  uint32_t time_ms; // 4
456  const Vector3f *body_offset;// 5..7
457  };
458 
460  bool frameIsNED; // true if the data is in a NED navigation frame
461  bool unitsAreSI; // true if the data length units are scaled in metres
462  Vector3f pos; // XYZ position measured in a RH navigation frame (m)
463  Quaternion quat; // quaternion describing the rotation from navigation to body frame
464  float posErr; // spherical poition measurement error 1-std (m)
465  float angErr; // spherical angular measurement error 1-std (rad)
466  const Vector3f *body_offset;// pointer to XYZ position of the sensor in body frame (m)
467  uint32_t time_ms; // measurement timestamp (msec)
468  bool posReset; // true when the position measurement has been reset
469  };
470 
471  // update the navigation filter status
472  void updateFilterStatus(void);
473 
474  // update the quaternion, velocity and position states using IMU measurements
476 
477  // calculate the predicted state covariance matrix
478  void CovariancePrediction();
479 
480  // force symmetry on the state covariance matrix
481  void ForceSymmetry();
482 
483  // copy covariances across from covariance prediction calculation and fix numerical errors
484  void CopyCovariances();
485 
486  // constrain variances (diagonal terms) in the state covariance matrix
487  void ConstrainVariances();
488 
489  // constrain states
490  void ConstrainStates();
491 
492  // fuse selected position, velocity and height measurements
493  void FuseVelPosNED();
494 
495  // fuse range beacon measurements
496  void FuseRngBcn();
497 
498  // use range beaon measurements to calculate a static position
499  void FuseRngBcnStatic();
500 
501  // calculate the offset from EKF vetical position datum to the range beacon system datum
502  void CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning);
503 
504  // fuse magnetometer measurements
505  void FuseMagnetometer();
506 
507  // fuse true airspeed measurements
508  void FuseAirspeed();
509 
510  // fuse sythetic sideslip measurement of zero
511  void FuseSideslip();
512 
513  // zero specified range of rows in the state covariance matrix
514  void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last);
515 
516  // zero specified range of columns in the state covariance matrix
517  void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last);
518 
519  // Reset the stored output history to current data
520  void StoreOutputReset(void);
521 
522  // Reset the stored output quaternion history to current EKF state
523  void StoreQuatReset(void);
524 
525  // Rotate the stored output quaternion history through a quaternion rotation
526  void StoreQuatRotate(Quaternion deltaQuat);
527 
528  // store altimeter data
529  void StoreBaro();
530 
531  // recall altimeter data at the fusion time horizon
532  // return true if data found
533  bool RecallBaro();
534 
535  // store range finder data
536  void StoreRange();
537 
538  // recall range finder data at the fusion time horizon
539  // return true if data found
540  bool RecallRange();
541 
542  // store magnetometer data
543  void StoreMag();
544 
545  // recall magetometer data at the fusion time horizon
546  // return true if data found
547  bool RecallMag();
548 
549  // store true airspeed data
550  void StoreTAS();
551 
552  // recall true airspeed data at the fusion time horizon
553  // return true if data found
554  bool RecallTAS();
555 
556  // store optical flow data
557  void StoreOF();
558 
559  // recall optical flow data at the fusion time horizon
560  // return true if data found
561  bool RecallOF();
562 
563  // calculate nav to body quaternions from body to nav rotation matrix
564  void quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const;
565 
566  // calculate the NED earth spin vector in rad/sec
567  void calcEarthRateNED(Vector3f &omega, int32_t latitude) const;
568 
569  // initialise the covariance matrix
570  void CovarianceInit();
571 
572  // helper functions for readIMUData
573  bool readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt);
574  bool readDeltaAngle(uint8_t ins_index, Vector3f &dAng, float &dAng_dt);
575 
576  // helper functions for correcting IMU data
577  void correctDeltaAngle(Vector3f &delAng, float delAngDT);
578  void correctDeltaVelocity(Vector3f &delVel, float delVelDT);
579 
580  // update IMU delta angle and delta velocity measurements
581  void readIMUData();
582 
583  // check for new valid GPS data and update stored measurement if available
584  void readGpsData();
585 
586  // check for new altitude measurement data and update stored measurement if available
587  void readBaroData();
588 
589  // check for new magnetometer data and update store measurements if available
590  void readMagData();
591 
592  // check for new airspeed data and update stored measurements if available
593  void readAirSpdData();
594 
595  // check for new range beacon data and update stored measurements if available
596  void readRngBcnData();
597 
598  // determine when to perform fusion of GPS position and velocity measurements
599  void SelectVelPosFusion();
600 
601  // determine when to perform fusion of range measurements take realtive to a beacon at a known NED position
602  void SelectRngBcnFusion();
603 
604  // determine when to perform fusion of magnetometer measurements
605  void SelectMagFusion();
606 
607  // determine when to perform fusion of true airspeed measurements
608  void SelectTasFusion();
609 
610  // determine when to perform fusion of synthetic sideslp measurements
611  void SelectBetaFusion();
612 
613  // force alignment of the yaw angle using GPS velocity data
614  void realignYawGPS();
615 
616  // initialise the earth magnetic field states using declination and current attitude and magnetometer meaasurements
617  // and return attitude quaternion
618  Quaternion calcQuatAndFieldStates(float roll, float pitch);
619 
620  // zero stored variables
621  void InitialiseVariables();
622 
623  // reset the horizontal position states uing the last GPS measurement
624  void ResetPosition(void);
625 
626  // reset velocity states using the last GPS measurement
627  void ResetVelocity(void);
628 
629  // reset the vertical position state using the last height measurement
630  void ResetHeight(void);
631 
632  // return true if we should use the airspeed sensor
633  bool useAirspeed(void) const;
634 
635  // return true if the vehicle code has requested the filter to be ready for flight
636  bool readyToUseGPS(void) const;
637 
638  // return true if the filter to be ready to use the beacon range measurements
639  bool readyToUseRangeBeacon(void) const;
640 
641  // return true if the filter to be ready to use external nav data
642  bool readyToUseExtNav(void) const;
643 
644  // Check for filter divergence
645  void checkDivergence(void);
646 
647  // Calculate weighting that is applied to IMU1 accel data to blend data from IMU's 1 and 2
648  void calcIMU_Weighting(float K1, float K2);
649 
650  // return true if optical flow data is available
651  bool optFlowDataPresent(void) const;
652 
653  // return true if we should use the range finder sensor
654  bool useRngFinder(void) const;
655 
656  // determine when to perform fusion of optical flow measurements
657  void SelectFlowFusion();
658 
659  // Estimate terrain offset using a single state EKF
660  void EstimateTerrainOffset();
661 
662  // fuse optical flow measurements into the main filter
663  void FuseOptFlow();
664 
665  // Control filter mode changes
666  void controlFilterModes();
667 
668  // Determine if we are flying or on the ground
669  void detectFlight();
670 
671  // Set inertial navigaton aiding mode
672  void setAidingMode();
673 
674  // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
675  // avoid unnecessary operations
677 
678  // Check the alignmnent status of the tilt attitude
679  // Used during initial bootstrap alignment of the filter
681 
682  // Control reset of yaw and magnetic field states
683  void controlMagYawReset();
684 
685  // Set the NED origin to be used until the next filter reset
686  void setOrigin();
687 
688  // determine if a takeoff is expected so that we can compensate for expected barometer errors due to ground effect
689  bool getTakeoffExpected();
690 
691  // determine if a touchdown is expected so that we can compensate for expected barometer errors due to ground effect
692  bool getTouchdownExpected();
693 
694  // Assess GPS data quality and return true if good enough to align the EKF
695  bool calcGpsGoodToAlign(void);
696 
697  // return true and set the class variable true if the delta angle bias has been learned
698  bool checkGyroCalStatus(void);
699 
700  // update inflight calculaton that determines if GPS data is good enough for reliable navigation
701  void calcGpsGoodForFlight(void);
702 
703  // Read the range finder and take new measurements if available
704  // Apply a median filter to range finder data
705  void readRangeFinder();
706 
707  // check if the vehicle has taken off during optical flow navigation by looking at inertial and range finder data
708  void detectOptFlowTakeoff(void);
709 
710  // align the NE earth magnetic field states with the published declination
712 
713  // Fuse compass measurements using a simple declination observation (doesn't require magnetic field states)
714  void fuseEulerYaw();
715 
716  // Fuse declination angle to keep earth field declination from changing when we don't have earth relative observations.
717  // Input is 1-sigma uncertainty in published declination
718  void FuseDeclination(float declErr);
719 
720  // Propagate PVA solution forward from the fusion time horizon to the current time horizon
721  // using a simple observer
722  void calcOutputStates();
723 
724  // calculate a filtered offset between baro height measurement and EKF height estimate
725  void calcFiltBaroOffset();
726 
727  // correct the height of the EKF origin to be consistent with GPS Data using a Bayes filter.
728  void correctEkfOriginHeight();
729 
730  // Select height data to be fused from the available baro, range finder and GPS sources
731  void selectHeightForFusion();
732 
733  // zero attitude state covariances, but preserve variances
734  void zeroAttCovOnly();
735 
736  // record a yaw reset event
737  void recordYawReset();
738 
739  // record a magnetic field state reset event
740  void recordMagReset();
741 
742  // effective value of MAG_CAL
743  uint8_t effective_magCal(void) const;
744 
745  // update timing statistics structure
746  void updateTimingStatistics(void);
747 
748  // Length of FIFO buffers used for non-IMU sensor data.
749  // Must be larger than the time period defined by IMU_BUFFER_LENGTH
750  static const uint32_t OBS_BUFFER_LENGTH = 5;
751 
752  // Variables
753  bool statesInitialised; // boolean true when filter states have been initialised
754  bool velHealth; // boolean true if velocity measurements have passed innovation consistency check
755  bool posHealth; // boolean true if position measurements have passed innovation consistency check
756  bool hgtHealth; // boolean true if height measurements have passed innovation consistency check
757  bool magHealth; // boolean true if magnetometer has passed innovation consistency check
758  bool tasHealth; // boolean true if true airspeed has passed innovation consistency check
759  bool velTimeout; // boolean true if velocity measurements have failed innovation consistency check and timed out
760  bool posTimeout; // boolean true if position measurements have failed innovation consistency check and timed out
761  bool hgtTimeout; // boolean true if height measurements have failed innovation consistency check and timed out
762  bool magTimeout; // boolean true if magnetometer measurements have failed for too long and have timed out
763  bool tasTimeout; // boolean true if true airspeed measurements have failed for too long and have timed out
764  bool badMagYaw; // boolean true if the magnetometer is declared to be producing bad data
765  bool badIMUdata; // boolean true if the bad IMU data is detected
766 
767  float gpsNoiseScaler; // Used to scale the GPS measurement noise and consistency gates to compensate for operation with small satellite counts
768  Vector28 Kfusion; // Kalman gain vector
769  Matrix24 KH; // intermediate result used for covariance updates
770  Matrix24 KHP; // intermediate result used for covariance updates
771  Matrix24 P; // covariance matrix
774  obs_ring_buffer_t<mag_elements> storedMag; // Magnetometer data buffer
777  obs_ring_buffer_t<range_elements> storedRange; // Range finder data buffer
779  Matrix3f prevTnb; // previous nav to body transformation used for INS earth rotation compensation
780  ftype accNavMag; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2)
781  ftype accNavMagHoriz; // magnitude of navigation accel in horizontal plane (m/s^2)
782  Vector3f earthRateNED; // earths angular rate vector in NED (rad/s)
783  ftype dtIMUavg; // expected time between IMU measurements (sec)
784  ftype dtEkfAvg; // expected time between EKF updates (sec)
785  ftype dt; // time lapsed since the last covariance prediction (sec)
786  ftype hgtRate; // state for rate of change of height filter
787  bool onGround; // true when the flight vehicle is definitely on the ground
788  bool prevOnGround; // value of onGround from previous frame - used to detect transition
789  bool inFlight; // true when the vehicle is definitely flying
790  bool prevInFlight; // value inFlight from previous frame - used to detect transition
791  bool manoeuvring; // boolean true when the flight vehicle is performing horizontal changes in velocity
792  uint32_t airborneDetectTime_ms; // last time flight movement was detected
793  Vector6 innovVelPos; // innovation output for a group of measurements
794  Vector6 varInnovVelPos; // innovation variance output for a group of measurements
795  Vector6 velPosObs; // observations for combined velocity and positon group of measurements (3x1 m , 3x1 m/s)
796  bool fuseVelData; // this boolean causes the velNED measurements to be fused
797  bool fusePosData; // this boolean causes the posNE measurements to be fused
798  bool fuseHgtData; // this boolean causes the hgtMea measurements to be fused
799  Vector3f innovMag; // innovation output from fusion of X,Y,Z compass measurements
800  Vector3f varInnovMag; // innovation variance output from fusion of X,Y,Z compass measurements
801  ftype innovVtas; // innovation output from fusion of airspeed measurements
802  ftype varInnovVtas; // innovation variance output from fusion of airspeed measurements
803  bool magFusePerformed; // boolean set to true when magnetometer fusion has been perfomred in that time step
804  bool magFuseRequired; // boolean set to true when magnetometer fusion will be perfomred in the next time step
805  uint32_t prevTasStep_ms; // time stamp of last TAS fusion step
806  uint32_t prevBetaStep_ms; // time stamp of last synthetic sideslip fusion step
807  uint32_t lastMagUpdate_us; // last time compass was updated in usec
808  Vector3f velDotNED; // rate of change of velocity in NED frame
809  Vector3f velDotNEDfilt; // low pass filtered velDotNED
810  uint32_t imuSampleTime_ms; // time that the last IMU value was taken
811  bool tasDataToFuse; // true when new airspeed data is waiting to be fused
812  uint32_t lastBaroReceived_ms; // time last time we received baro height data
813  uint16_t hgtRetryTime_ms; // time allowed without use of height measurements before a height timeout is declared
814  uint32_t lastVelPassTime_ms; // time stamp when GPS velocity measurement last passed innovation consistency check (msec)
815  uint32_t lastPosPassTime_ms; // time stamp when GPS position measurement last passed innovation consistency check (msec)
816  uint32_t lastHgtPassTime_ms; // time stamp when height measurement last passed innovation consistency check (msec)
817  uint32_t lastTasPassTime_ms; // time stamp when airspeed measurement last passed innovation consistency check (msec)
818  uint32_t lastTimeGpsReceived_ms;// last time we received GPS data
819  uint32_t timeAtLastAuxEKF_ms; // last time the auxiliary filter was run to fuse range or optical flow measurements
820  uint32_t secondLastGpsTime_ms; // time of second last GPS fix used to determine how long since last update
821  uint32_t lastHealthyMagTime_ms; // time the magnetometer was last declared healthy
822  bool allMagSensorsFailed; // true if all magnetometer sensors have timed out on this flight and we are no longer using magnetometer data
823  uint32_t lastYawTime_ms; // time stamp when yaw observation was last fused (msec)
824  uint32_t ekfStartTime_ms; // time the EKF was started (msec)
825  Matrix24 nextP; // Predicted covariance matrix before addition of process noise to diagonals
826  Vector24 processNoise; // process noise added to diagonals of predicted covariance matrix
827  Vector25 SF; // intermediate variables used to calculate predicted covariance matrix
828  Vector5 SG; // intermediate variables used to calculate predicted covariance matrix
829  Vector8 SQ; // intermediate variables used to calculate predicted covariance matrix
830  Vector23 SPP; // intermediate variables used to calculate predicted covariance matrix
831  Vector2f lastKnownPositionNE; // last known position
832  uint32_t lastDecayTime_ms; // time of last decay of GPS position offset
833  float velTestRatio; // sum of squares of GPS velocity innovation divided by fail threshold
834  float posTestRatio; // sum of squares of GPS position innovation divided by fail threshold
835  float hgtTestRatio; // sum of squares of baro height innovation divided by fail threshold
836  Vector3f magTestRatio; // sum of squares of magnetometer innovations divided by fail threshold
837  float tasTestRatio; // sum of squares of true airspeed innovation divided by fail threshold
838  bool inhibitWindStates; // true when wind states and covariances are to remain constant
839  bool inhibitMagStates; // true when magnetic field states and covariances are to remain constant
840  bool gpsNotAvailable; // bool true when valid GPS data is not available
841  uint8_t last_gps_idx; // sensor ID of the GPS receiver used for the last fusion or reset
842  struct Location EKF_origin; // LLH origin of the NED axis system
843  bool validOrigin; // true when the EKF origin is valid
844  float gpsSpdAccuracy; // estimated speed accuracy in m/s returned by the GPS receiver
845  float gpsPosAccuracy; // estimated position accuracy in m returned by the GPS receiver
846  float gpsHgtAccuracy; // estimated height accuracy in m returned by the GPS receiver
847  uint32_t lastGpsVelFail_ms; // time of last GPS vertical velocity consistency check fail
848  uint32_t lastGpsAidBadTime_ms; // time in msec gps aiding was last detected to be bad
849  float posDownAtTakeoff; // flight vehicle vertical position sampled at transition from on-ground to in-air and used as a reference (m)
850  bool useGpsVertVel; // true if GPS vertical velocity should be used
851  float yawResetAngle; // Change in yaw angle due to last in-flight yaw reset in radians. A positive value means the yaw angle has increased.
852  uint32_t lastYawReset_ms; // System time at which the last yaw reset occurred. Returned by getLastYawResetAngle
853  Vector3f tiltErrVec; // Vector of most recent attitude error correction from Vel,Pos fusion
854  float tiltErrFilt; // Filtered tilt error metric
855  bool tiltAlignComplete; // true when tilt alignment is complete
856  bool yawAlignComplete; // true when yaw alignment is complete
857  bool magStateInitComplete; // true when the magnetic field sttes have been initialised
858  uint8_t stateIndexLim; // Max state index used during matrix and array operations
859  imu_elements imuDataDelayed; // IMU data at the fusion time horizon
860  imu_elements imuDataNew; // IMU data at the current time horizon
861  imu_elements imuDataDownSampledNew; // IMU data at the current time horizon that has been downsampled to a 100Hz rate
862  Quaternion imuQuatDownSampleNew; // Quaternion obtained by rotating through the IMU delta angles since the start of the current down sampled frame
863  uint8_t fifoIndexNow; // Global index for inertial and output solution at current time horizon
864  uint8_t fifoIndexDelayed; // Global index for inertial and output solution at delayed/fusion time horizon
865  baro_elements baroDataNew; // Baro data at the current time horizon
866  baro_elements baroDataDelayed; // Baro data at the fusion time horizon
867  uint8_t baroStoreIndex; // Baro data storage index
868  range_elements rangeDataNew; // Range finder data at the current time horizon
869  range_elements rangeDataDelayed;// Range finder data at the fusion time horizon
870  uint8_t rangeStoreIndex; // Range finder data storage index
871  tas_elements tasDataNew; // TAS data at the current time horizon
872  tas_elements tasDataDelayed; // TAS data at the fusion time horizon
873  uint8_t tasStoreIndex; // TAS data storage index
874  mag_elements magDataNew; // Magnetometer data at the current time horizon
875  mag_elements magDataDelayed; // Magnetometer data at the fusion time horizon
876  uint8_t magStoreIndex; // Magnetometer data storage index
877  gps_elements gpsDataNew; // GPS data at the current time horizon
878  gps_elements gpsDataDelayed; // GPS data at the fusion time horizon
879  uint8_t gpsStoreIndex; // GPS data storage index
880  output_elements outputDataNew; // output state data at the current time step
881  output_elements outputDataDelayed; // output state data at the current time step
882  Vector3f delAngCorrection; // correction applied to delta angles used by output observer to track the EKF
883  Vector3f velErrintegral; // integral of output predictor NED velocity tracking error (m)
884  Vector3f posErrintegral; // integral of output predictor NED position tracking error (m.sec)
885  float innovYaw; // compass yaw angle innovation (rad)
886  uint32_t timeTasReceived_ms; // time last TAS data was received (msec)
887  bool gpsGoodToAlign; // true when the GPS quality can be used to initialise the navigation system
888  uint32_t magYawResetTimer_ms; // timer in msec used to track how long good magnetometer data is failing innovation consistency checks
889  bool consistentMagData; // true when the magnetometers are passing consistency checks
890  bool motorsArmed; // true when the motors have been armed
891  bool prevMotorsArmed; // value of motorsArmed from previous frame
892  bool posVelFusionDelayed; // true when the position and velocity fusion has been delayed
893  bool optFlowFusionDelayed; // true when the optical flow fusion has been delayed
894  bool airSpdFusionDelayed; // true when the air speed fusion has been delayed
895  bool sideSlipFusionDelayed; // true when the sideslip fusion has been delayed
896  Vector3f lastMagOffsets; // Last magnetometer offsets from COMPASS_ parameters. Used to detect parameter changes.
897  bool lastMagOffsetsValid; // True when lastMagOffsets has been initialized
898  Vector2f posResetNE; // Change in North/East position due to last in-flight reset in metres. Returned by getLastPosNorthEastReset
899  uint32_t lastPosReset_ms; // System time at which the last position reset occurred. Returned by getLastPosNorthEastReset
900  Vector2f velResetNE; // Change in North/East velocity due to last in-flight reset in metres/sec. Returned by getLastVelNorthEastReset
901  uint32_t lastVelReset_ms; // System time at which the last velocity reset occurred. Returned by getLastVelNorthEastReset
902  float posResetD; // Change in Down position due to last in-flight reset in metres. Returned by getLastPosDowntReset
903  uint32_t lastPosResetD_ms; // System time at which the last position reset occurred. Returned by getLastPosDownReset
904  float yawTestRatio; // square of magnetometer yaw angle innovation divided by fail threshold
905  Quaternion prevQuatMagReset; // Quaternion from the last time the magnetic field state reset condition test was performed
906  uint8_t fusionHorizonOffset; // number of IMU samples that the fusion time horizon has been shifted to prevent multiple EKF instances fusing data at the same time
907  float hgtInnovFiltState; // state used for fitering of the height innovations used for pre-flight checks
908  uint8_t magSelectIndex; // Index of the magnetometer that is being used by the EKF
909  bool runUpdates; // boolean true when the EKF updates can be run
910  uint32_t framesSincePredict; // number of frames lapsed since EKF instance did a state prediction
911  bool startPredictEnabled; // boolean true when the frontend has given permission to start a new state prediciton cycele
912  uint8_t localFilterTimeStep_ms; // average number of msec between filter updates
913  float posDownObsNoise; // observation noise variance on the vertical position used by the state and covariance update step (m^2)
914  Vector3f delAngCorrected; // corrected IMU delta angle vector at the EKF time horizon (rad)
915  Vector3f delVelCorrected; // corrected IMU delta velocity vector at the EKF time horizon (m/s)
916  bool magFieldLearned; // true when the magnetic field has been learned
917  Vector3f earthMagFieldVar; // NED earth mag field variances for last learned field (mGauss^2)
918  Vector3f bodyMagFieldVar; // XYZ body mag field variances for last learned field (mGauss^2)
919  bool delAngBiasLearned; // true when the gyro bias has been learned
920  nav_filter_status filterStatus; // contains the status of various filter outputs
921  float ekfOriginHgtVar; // Variance of the the EKF WGS-84 origin height estimate (m^2)
922  double ekfGpsRefHgt; // floating point representation of the WGS-84 reference height used to convert GPS height to local height (m)
923  uint32_t lastOriginHgtTime_ms; // last time the ekf's WGS-84 origin height was corrected
924  Vector3f outputTrackError; // attitude (rad), velocity (m/s) and position (m) tracking error magnitudes from the output observer
925  Vector3f velOffsetNED; // This adds to the earth frame velocity estimate at the IMU to give the velocity at the body origin (m/s)
926  Vector3f posOffsetNED; // This adds to the earth frame position estimate at the IMU to give the position at the body origin (m)
927 
928  // variables used to calculate a vertical velocity that is kinematically consistent with the verical position
929  float posDownDerivative; // Rate of chage of vertical position (dPosD/dt) in m/s. This is the first time derivative of PosD.
930  float posDown; // Down position state used in calculation of posDownRate
931 
932  // variables used by the pre-initialisation GPS checks
933  struct Location gpsloc_prev; // LLH location of previous GPS measurement
934  uint32_t lastPreAlignGpsCheckTime_ms; // last time in msec the GPS quality was checked during pre alignment checks
935  float gpsDriftNE; // amount of drift detected in the GPS position during pre-flight GPs checks
936  float gpsVertVelFilt; // amount of filterred vertical GPS velocity detected durng pre-flight GPS checks
937  float gpsHorizVelFilt; // amount of filtered horizontal GPS velocity detected during pre-flight GPS checks
938 
939  // variable used by the in-flight GPS quality check
940  bool gpsSpdAccPass; // true when reported GPS speed accuracy passes in-flight checks
941  bool ekfInnovationsPass; // true when GPS innovations pass in-flight checks
942  float sAccFilterState1; // state variable for LPF applid to reported GPS speed accuracy
943  float sAccFilterState2; // state variable for peak hold filter applied to reported GPS speed
944  uint32_t lastGpsCheckTime_ms; // last time in msec the GPS quality was checked
945  uint32_t lastInnovPassTime_ms; // last time in msec the GPS innovations passed
946  uint32_t lastInnovFailTime_ms; // last time in msec the GPS innovations failed
947  bool gpsAccuracyGood; // true when the GPS accuracy is considered to be good enough for safe flight.
948 
949  // States used for unwrapping of compass yaw error
952 
953  // variables added for optical flow fusion
955  of_elements ofDataNew; // OF data at the current time horizon
956  of_elements ofDataDelayed; // OF data at the fusion time horizon
957  uint8_t ofStoreIndex; // OF data storage index
958  bool flowDataToFuse; // true when optical flow data has is ready for fusion
959  bool flowDataValid; // true while optical flow data is still fresh
960  bool fuseOptFlowData; // this boolean causes the last optical flow measurement to be fused
961  float auxFlowObsInnov; // optical flow rate innovation from 1-state terrain offset estimator
962  float auxFlowObsInnovVar; // innovation variance for optical flow observations from 1-state terrain offset estimator
963  uint32_t flowValidMeaTime_ms; // time stamp from latest valid flow measurement (msec)
964  uint32_t rngValidMeaTime_ms; // time stamp from latest valid range measurement (msec)
965  uint32_t flowMeaTime_ms; // time stamp from latest flow measurement (msec)
966  uint32_t gndHgtValidTime_ms; // time stamp from last terrain offset state update (msec)
967  Matrix3f Tbn_flow; // transformation matrix from body to nav axes at the middle of the optical flow sample period
968  Vector2 varInnovOptFlow; // optical flow innovations variances (rad/sec)^2
969  Vector2 innovOptFlow; // optical flow LOS innovations (rad/sec)
970  float Popt; // Optical flow terrain height state covariance (m^2)
971  float terrainState; // terrain position state (m)
972  float prevPosN; // north position at last measurement
973  float prevPosE; // east position at last measurement
974  float varInnovRng; // range finder observation innovation variance (m^2)
975  float innovRng; // range finder observation innovation (m)
976  float hgtMea; // height measurement derived from either baro, gps or range finder data (m)
977  bool inhibitGndState; // true when the terrain position state is to remain constant
978  uint32_t prevFlowFuseTime_ms; // time both flow measurement components passed their innovation consistency checks
979  Vector2 flowTestRatio; // square of optical flow innovations divided by fail threshold used by main filter where >1.0 is a fail
980  float auxFlowTestRatio; // sum of squares of optical flow innovation divided by fail threshold used by 1-state terrain offset estimator
981  float R_LOS; // variance of optical flow rate measurements (rad/sec)^2
982  float auxRngTestRatio; // square of range finder innovations divided by fail threshold used by main filter where >1.0 is a fail
983  Vector2f flowGyroBias; // bias error of optical flow sensor gyro output
984  bool rangeDataToFuse; // true when valid range finder height data has arrived at the fusion time horizon.
985  bool baroDataToFuse; // true when valid baro height finder data has arrived at the fusion time horizon.
986  bool gpsDataToFuse; // true when valid GPS data has arrived at the fusion time horizon.
987  bool magDataToFuse; // true when valid magnetometer data has arrived at the fusion time horizon
988  Vector2f heldVelNE; // velocity held when no aiding is available
989  enum AidingMode {AID_ABSOLUTE=0, // GPS or some other form of absolute position reference aiding is being used (optical flow may also be used in parallel) so position estimates are absolute.
990  AID_NONE=1, // no aiding is being used so only attitude and height estimates are available. Either constVelMode or constPosMode must be used to constrain tilt drift.
991  AID_RELATIVE=2 // only optical flow aiding is being used so position estimates will be relative
992  };
993  AidingMode PV_AidingMode; // Defines the preferred mode for aiding of velocity and position estimates from the INS
994  AidingMode PV_AidingModePrev; // Value of PV_AidingMode from the previous frame - used to detect transitions
995  bool gpsInhibit; // externally set flag informing the EKF not to use the GPS
996  bool gndOffsetValid; // true when the ground offset state can still be considered valid
997  Vector3f delAngBodyOF; // bias corrected delta angle of the vehicle IMU measured summed across the time since the last OF measurement
998  float delTimeOF; // time that delAngBodyOF is summed across
999  Vector3f accelPosOffset; // position of IMU accelerometer unit in body frame (m)
1000 
1001 
1002  // Range finder
1003  float baroHgtOffset; // offset applied when when switching to use of Baro height
1004  float rngOnGnd; // Expected range finder reading in metres when vehicle is on ground
1005  float storedRngMeas[2][3]; // Ringbuffer of stored range measurements for dual range sensors
1006  uint32_t storedRngMeasTime_ms[2][3]; // Ringbuffers of stored range measurement times for dual range sensors
1007  uint32_t lastRngMeasTime_ms; // Timestamp of last range measurement
1008  uint8_t rngMeasIndex[2]; // Current range measurement ringbuffer index for dual range sensors
1009  bool terrainHgtStable; // true when the terrain height is stable enough to be used as a height reference
1010  uint32_t terrainHgtStableSet_ms; // system time at which terrainHgtStable was set
1011 
1012  // Range Beacon Sensor Fusion
1014  rng_bcn_elements rngBcnDataNew; // Range beacon data at the current time horizon
1015  rng_bcn_elements rngBcnDataDelayed; // Range beacon data at the fusion time horizon
1016  uint8_t rngBcnStoreIndex; // Range beacon data storage index
1017  uint32_t lastRngBcnPassTime_ms; // time stamp when the range beacon measurement last passed innvovation consistency checks (msec)
1018  float rngBcnTestRatio; // Innovation test ratio for range beacon measurements
1019  bool rngBcnHealth; // boolean true if range beacon measurements have passed innovation consistency check
1020  bool rngBcnTimeout; // boolean true if range beacon measurements have faled innovation consistency checks for too long
1021  float varInnovRngBcn; // range beacon observation innovation variance (m^2)
1022  float innovRngBcn; // range beacon observation innovation (m)
1023  uint32_t lastTimeRngBcn_ms[10]; // last time we received a range beacon measurement (msec)
1024  bool rngBcnDataToFuse; // true when there is new range beacon data to fuse
1025  Vector3f beaconVehiclePosNED; // NED position estimate from the beacon system (NED)
1026  float beaconVehiclePosErr; // estimated position error from the beacon system (m)
1027  uint32_t rngBcnLast3DmeasTime_ms; // last time the beacon system returned a 3D fix (msec)
1028  bool rngBcnGoodToAlign; // true when the range beacon systems 3D fix can be used to align the filter
1029  uint8_t lastRngBcnChecked; // index of the last range beacon checked for data
1030  Vector3f receiverPos; // receiver NED position (m) - alignment 3 state filter
1031  float receiverPosCov[3][3]; // Receiver position covariance (m^2) - alignment 3 state filter (
1032  bool rngBcnAlignmentStarted; // True when the initial position alignment using range measurements has started
1033  bool rngBcnAlignmentCompleted; // True when the initial position alignment using range measurements has finished
1034  uint8_t lastBeaconIndex; // Range beacon index last read - used during initialisation of the 3-state filter
1035  Vector3f rngBcnPosSum; // Sum of range beacon NED position (m) - used during initialisation of the 3-state filter
1036  uint8_t numBcnMeas; // Number of beacon measurements - used during initialisation of the 3-state filter
1037  float rngSum; // Sum of range measurements (m) - used during initialisation of the 3-state filter
1038  uint8_t N_beacons; // Number of range beacons in use
1039  float maxBcnPosD; // maximum position of all beacons in the down direction (m)
1040  float minBcnPosD; // minimum position of all beacons in the down direction (m)
1041  float bcnPosOffset; // Vertical position offset of the beacon constellation origin relative to the EKF origin (m)
1042 
1043  float bcnPosOffsetMax; // Vertical position offset of the beacon constellation origin relative to the EKF origin (m)
1044  float bcnPosOffsetMaxVar; // Variance of the bcnPosOffsetHigh state (m)
1045  float OffsetMaxInnovFilt; // Filtered magnitude of the range innovations using bcnPosOffsetHigh
1046 
1047  float bcnPosOffsetMin; // Vertical position offset of the beacon constellation origin relative to the EKF origin (m)
1048  float bcnPosOffsetMinVar; // Variance of the bcnPosoffset state (m)
1049  float OffsetMinInnovFilt; // Filtered magnitude of the range innovations using bcnPosOffsetLow
1050 
1051  // Range Beacon Fusion Debug Reporting
1052  uint8_t rngBcnFuseDataReportIndex;// index of range beacon fusion data last reported
1053  struct {
1054  float rng; // measured range to beacon (m)
1055  float innov; // range innovation (m)
1056  float innovVar; // innovation variance (m^2)
1057  float testRatio; // innovation consistency test ratio
1058  Vector3f beaconPosNED; // beacon NED position
1059  } rngBcnFusionReport[10];
1060 
1061  // height source selection logic
1062  uint8_t activeHgtSource; // integer defining active height source
1063 
1064  // Movement detector
1065  bool takeOffDetected; // true when takeoff for optical flow navigation has been detected
1066  float rngAtStartOfFlight; // range finder measurement at start of flight
1067  uint32_t timeAtArming_ms; // time in msec that the vehicle armed
1068 
1069  // baro ground effect
1070  bool expectGndEffectTakeoff; // external state from ArduCopter - takeoff expected
1071  uint32_t takeoffExpectedSet_ms; // system time at which expectGndEffectTakeoff was set
1072  bool expectGndEffectTouchdown; // external state from ArduCopter - touchdown expected
1073  uint32_t touchdownExpectedSet_ms; // system time at which expectGndEffectTouchdown was set
1074  float meaHgtAtTakeOff; // height measured at commencement of takeoff
1075 
1076  // control of post takeoff magentic field and heading resets
1077  bool finalInflightYawInit; // true when the final post takeoff initialisation of yaw angle has been performed
1078  bool finalInflightMagInit; // true when the final post takeoff initialisation of magnetic field states been performed
1079  bool magStateResetRequest; // true if magnetic field states need to be reset using the magneteomter measurements
1080  bool magYawResetRequest; // true if the vehicle yaw and magnetic field states need to be reset using the magnetometer measurements
1081  bool gpsYawResetRequest; // true if the vehicle yaw needs to be reset to the GPS course
1082  float posDownAtLastMagReset; // vertical position last time the mag states were reset (m)
1083  float yawInnovAtLastMagReset; // magnetic yaw innovation last time the yaw and mag field states were reset (rad)
1084  Quaternion quatAtLastMagReset; // quaternion states last time the mag states were reset
1085 
1086  // external navigation fusion
1087  obs_ring_buffer_t<ext_nav_elements> storedExtNav; // external navigation data buffer
1088  ext_nav_elements extNavDataNew; // External nav data at the current time horizon
1089  ext_nav_elements extNavDataDelayed; // External nav at the fusion time horizon
1090  uint32_t extNavMeasTime_ms; // time external measurements were accepted for input to the data buffer (msec)
1091  uint32_t extNavLastPosResetTime_ms; // last time the external nav systen performed a position reset (msec)
1092  bool extNavDataToFuse; // true when there is new external nav data to fuse
1093  bool extNavUsedForYaw; // true when the external nav data is also being used as a yaw observation
1094  bool extNavUsedForPos; // true when the external nav data is being used as a position reference.
1095  bool extNavYawResetRequest; // true when a reset of vehicle yaw using the external nav data is requested
1096 
1097  // flags indicating severe numerical errors in innovation variance calculation for different fusion operations
1098  struct {
1099  bool bad_xmag:1;
1100  bool bad_ymag:1;
1101  bool bad_zmag:1;
1104  bool bad_nvel:1;
1105  bool bad_evel:1;
1106  bool bad_dvel:1;
1107  bool bad_npos:1;
1108  bool bad_epos:1;
1109  bool bad_dpos:1;
1110  bool bad_yaw:1;
1111  bool bad_decl:1;
1112  bool bad_xflow:1;
1113  bool bad_yflow:1;
1114  bool bad_rngbcn:1;
1115  } faultStatus;
1116 
1117  // flags indicating which GPS quality checks are failing
1118  struct {
1119  bool bad_sAcc:1;
1120  bool bad_hAcc:1;
1121  bool bad_vAcc:1;
1122  bool bad_yaw:1;
1123  bool bad_sats:1;
1124  bool bad_VZ:1;
1126  bool bad_hdop:1;
1128  bool bad_fix:1;
1130  } gpsCheckStatus;
1131 
1132  // states held by magnetomter fusion across time steps
1133  // magnetometer X,Y,Z measurements are fused across three time steps
1134  // to level computational load as this is an expensive operation
1135  struct {
1136  ftype q0;
1137  ftype q1;
1138  ftype q2;
1139  ftype q3;
1140  ftype magN;
1141  ftype magE;
1142  ftype magD;
1143  ftype magXbias;
1144  ftype magYbias;
1145  ftype magZbias;
1146  uint8_t obsIndex;
1149  ftype R_MAG;
1150  Vector9 SH_MAG;
1151  } mag_state;
1152 
1153  // string representing last reason for prearm failure
1155 
1156  // performance counters
1166 
1167  // timing statistics
1168  struct ekf_timing timing;
1169 
1170  // should we assume zero sideslip?
1171  bool assume_zero_sideslip(void) const;
1172 
1173  // vehicle specific initial gyro bias uncertainty
1174  float InitialGyroBiasUncertainty(void) const;
1175 };
uint32_t lastVelReset_ms
bool RecallMag()
Vector2f posResetNE
uint8_t rngMeasIndex[2]
Vector3f tiltErrVec
gps_elements gpsDataDelayed
uint32_t lastVelPassTime_ms
ftype Vector6[6]
uint8_t fifoIndexDelayed
uint8_t effective_magCal(void) const
void correctDeltaAngle(Vector3f &delAng, float delAngDT)
void calcIMU_Weighting(float K1, float K2)
struct Location gpsloc_prev
uint32_t lastBaroReceived_ms
obs_ring_buffer_t< gps_elements > storedGPS
uint32_t getLastPosDownReset(float &posD) const
uint32_t extNavMeasTime_ms
Vector3f earthRateNED
ftype Vector23[23]
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
Quaternion quatAtLastMagReset
void getAccelZBias(float &zbias) const
Vector3f accelPosOffset
imu_ring_buffer_t< output_elements > storedOutput
bool posVelFusionDelayed
void CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning)
uint32_t Vector_u32_50[50]
bool extNavYawResetRequest
void getWind(Vector3f &wind) const
bool getLLH(struct Location &loc) const
char prearm_fail_string[40]
uint32_t prevTasStep_ms
uint32_t lastPosReset_ms
AP_HAL::Util::perf_counter_t _perf_FuseSideslip
Quaternion prevQuatMagReset
gps_elements gpsDataNew
void InitialiseVariables()
void UpdateStrapdownEquationsNED()
void StoreMag()
float posDownAtTakeoff
Vector3f posErrintegral
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
mag_elements magDataNew
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
ftype Vector10[10]
uint8_t magStoreIndex
baro_elements baroDataNew
void StoreTAS()
mag_elements magDataDelayed
output_elements outputDataNew
Vector6 varInnovVelPos
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow)
NavEKF2 * frontend
void StoreBaro()
bool assume_zero_sideslip(void) const
Vector3f magTestRatio
float auxFlowTestRatio
ftype Vector9[9]
void checkDivergence(void)
ftype Matrix34_50[34][50]
float rngAtStartOfFlight
Vector28 statesArray
ftype Vector15[15]
Vector3f velDotNEDfilt
const AP_AHRS * _ahrs
float yawInnovAtLastMagReset
obs_ring_buffer_t< range_elements > storedRange
bool healthy(void) const
uint32_t lastRngMeasTime_ms
Vector2 varInnovOptFlow
ext_nav_elements extNavDataNew
Vector2 innovOptFlow
struct NavEKF2_core::@147 mag_state
void getRotationBodyToNED(Matrix3f &mat) const
void getTimingStatistics(struct ekf_timing &timing)
uint8_t gpsStoreIndex
Vector2f flowGyroBias
const char * prearm_failure_reason(void) const
Vector3f delAngBodyOF
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
void CovariancePrediction()
uint8_t core_index
float beaconVehiclePosErr
uint16_t hgtRetryTime_ms
uint8_t fusionHorizonOffset
float hgtInnovFiltState
void getFilterFaults(uint16_t &faults) const
bool getHeightControlLimit(float &height) const
float OffsetMinInnovFilt
uint32_t magYawResetTimer_ms
void updateFilterStatus(void)
float storedRngMeas[2][3]
void getVelNED(Vector3f &vel) const
uint32_t lastDecayTime_ms
Vector3f rngBcnPosSum
Vector3f bodyMagFieldVar
bool setup_core(NavEKF2 *_frontend, uint8_t _imu_index, uint8_t _core_index)
bool optFlowFusionDelayed
uint32_t lastHgtPassTime_ms
bool getPosNE(Vector2f &posNE) const
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
output_elements outputDataDelayed
bool InitialiseFilterBootstrap(void)
Vector2f heldVelNE
obs_ring_buffer_t< tas_elements > storedTAS
uint32_t lastInnovFailTime_ms
uint32_t lastInnovPassTime_ms
void quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
void getFilterGpsStatus(nav_gps_status &status) const
imu_elements imuDataDelayed
uint32_t lastPreAlignGpsCheckTime_ms
uint8_t setInhibitGPS(void)
Matrix3f Tbn_flow
void getMagNED(Vector3f &magNED) const
uint32_t framesSincePredict
ftype Vector5[5]
Vector3f earthMagFieldVar
bool readyToUseGPS(void) const
void getAccelNED(Vector3f &accelNED) const
void setTakeoffExpected(bool val)
float bcnPosOffsetMaxVar
void send_status_report(mavlink_channel_t chan)
bool readyToUseRangeBeacon(void) const
baro_elements baroDataDelayed
float receiverPosCov[3][3]
uint32_t getLastYawResetAngle(float &yawAng) const
uint32_t airborneDetectTime_ms
bool readDeltaAngle(uint8_t ins_index, Vector3f &dAng, float &dAng_dt)
uint8_t lastBeaconIndex
AP_HAL::Util::perf_counter_t _perf_FuseAirspeed
Vector3f delVelCorrected
uint32_t secondLastGpsTime_ms
struct NavEKF2_core::@145 faultStatus
uint8_t rngBcnFuseDataReportIndex
ftype Vector22[22]
void * perf_counter_t
Definition: Util.h:101
bool optFlowDataPresent(void) const
uint8_t rngBcnStoreIndex
ftype Vector7[7]
ftype Vector28[28]
bool startPredictEnabled
uint8_t magSelectIndex
bool readyToUseExtNav(void) const
uint32_t lastHealthyMagTime_ms
float bcnPosOffsetMinVar
void getMagXYZ(Vector3f &magXYZ) const
uint32_t prevFlowFuseTime_ms
uint32_t prevBetaStep_ms
Vector3f varInnovMag
void getGyroBias(Vector3f &gyroBias) const
Vector3f velOffsetNED
struct NavEKF2_core::@146 gpsCheckStatus
const Vector3f * body_offset
bool RecallBaro()
uint8_t getIMUIndex(void) const
uint8_t rangeStoreIndex
float innovationIncrement
bool useAirspeed(void) const
bool getOriginLLH(struct Location &loc) const
uint8_t getFramesSincePredict(void) const
void setWindMagStateLearningMode()
float sAccFilterState2
float auxFlowObsInnovVar
ftype Vector2[2]
AidingMode PV_AidingModePrev
ftype Vector8[8]
float posDownAtLastMagReset
Vector3f innovMag
uint8_t activeHgtSource
bool useRngFinder(void) const
of_elements ofDataNew
uint32_t gndHgtValidTime_ms
uint32_t rngBcnLast3DmeasTime_ms
Vector3f velErrintegral
float getPosDownDerivative(void) const
Vector6 innovVelPos
static const uint32_t OBS_BUFFER_LENGTH
ftype Vector25[25]
obs_ring_buffer_t< mag_elements > storedMag
void getFilterTimeouts(uint8_t &timeouts) const
uint8_t tasStoreIndex
ftype Vector24[24]
Vector3f beaconVehiclePosNED
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
bool getHAGL(float &HAGL) const
float posDownDerivative
uint32_t lastMagUpdate_us
struct ekf_timing timing
Matrix3f prevTnb
void getOutputTrackingError(Vector3f &error) const
bool use_compass(void) const
AP_HAL::Util::perf_counter_t _perf_test[10]
void UpdateFilter(bool predict)
uint8_t ofStoreIndex
obs_ring_buffer_t< rng_bcn_elements > storedRangeBeacon
void getEulerAngles(Vector3f &eulers) const
bool magStateInitComplete
AP_HAL::Util::perf_counter_t _perf_FuseMagnetometer
bool sideSlipFusionDelayed
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
Vector3f delAngCorrected
void getQuaternion(Quaternion &quat) const
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
AP_HAL::Util::perf_counter_t _perf_UpdateFilter
ftype Vector11[11]
obs_ring_buffer_t< baro_elements > storedBaro
void StoreQuatReset(void)
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
uint32_t lastGpsAidBadTime_ms
uint32_t timeAtArming_ms
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
struct Location EKF_origin
uint32_t lastOriginHgtTime_ms
float errorScore(void) const
nav_filter_status filterStatus
bool setOriginLLH(const Location &loc)
ext_nav_elements extNavDataDelayed
float sAccFilterState1
Vector3f velDotNED
uint32_t lastRngBcnPassTime_ms
bool RecallRange()
uint8_t last_gps_idx
rng_bcn_elements rngBcnDataDelayed
Vector24 processNoise
uint32_t flowMeaTime_ms
Vector3f delAngCorrection
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
Vector3f posOffsetNED
tas_elements tasDataNew
uint8_t stateIndexLim
imu_ring_buffer_t< imu_elements > storedIMU
Vector2f velResetNE
AP_HAL::Util::perf_counter_t _perf_TerrainOffset
of_elements ofDataDelayed
#define error(fmt, args ...)
uint32_t lastTimeRngBcn_ms[10]
Vector3f outputTrackError
obs_ring_buffer_t< ext_nav_elements > storedExtNav
uint8_t getActiveMag() const
bool expectGndEffectTouchdown
bool airSpdFusionDelayed
void FuseDeclination(float declErr)
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
bool rngBcnAlignmentCompleted
Vector3f lastMagOffsets
bool RecallOF()
uint8_t localFilterTimeStep_ms
Vector2 flowTestRatio
ftype Vector4[4]
AP_HAL::Util::perf_counter_t _perf_FuseOptFlow
void resetGyroBias(void)
range_elements rangeDataNew
bool RecallTAS()
uint8_t lastRngBcnChecked
bool lastMagOffsetsValid
bool expectGndEffectTakeoff
uint32_t timeTasReceived_ms
uint32_t ekfStartTime_ms
void getGyroScaleErrorPercentage(Vector3f &gyroScale) const
range_elements rangeDataDelayed
float OffsetMaxInnovFilt
uint32_t lastPosPassTime_ms
uint32_t lastTasPassTime_ms
tas_elements tasDataDelayed
void StoreOF()
uint8_t baroStoreIndex
uint32_t extNavLastPosResetTime_ms
uint32_t rngValidMeaTime_ms
void updateTimingStatistics(void)
void setTouchdownExpected(bool val)
void StoreOutputReset(void)
AP_HAL::Util::perf_counter_t _perf_CovariancePrediction
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
void correctDeltaVelocity(Vector3f &delVel, float delVelDT)
uint32_t terrainHgtStableSet_ms
ftype Matrix24[24][24]
float InitialGyroBiasUncertainty(void) const
Quaternion imuQuatDownSampleNew
uint32_t storedRngMeasTime_ms[2][3]
void checkAttitudeAlignmentStatus()
uint32_t flowValidMeaTime_ms
bool readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt)
ftype Vector3[3]
uint8_t fifoIndexNow
void getFilterStatus(nav_filter_status &status) const
void setTerrainHgtStable(bool val)
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
void getTiltError(float &ang) const
Vector3f beaconPosNED
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
bool getPosD(float &posD) const
imu_elements imuDataNew
void StoreRange()
bool checkGyroCalStatus(void)
Vector28 Kfusion
bool allMagSensorsFailed
AidingMode PV_AidingMode
ftype Matrix3[3][3]
uint32_t lastPosResetD_ms
ftype Vector14[14]
ftype Vector13[13]
uint32_t lastYawTime_ms
imu_elements imuDataDownSampledNew
uint32_t lastGpsCheckTime_ms
void StoreQuatRotate(Quaternion deltaQuat)