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