APM:Libraries
AP_NavEKF3.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 #include <AP_Math/AP_Math.h>
23 #include <AP_Param/AP_Param.h>
26 #include <AP_Baro/AP_Baro.h>
28 #include <AP_Compass/AP_Compass.h>
30 
31 class NavEKF3_core;
32 class AP_AHRS;
33 
34 class NavEKF3 {
35  friend class NavEKF3_core;
36 
37 public:
38  NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng);
39 
40  /* Do not allow copies */
41  NavEKF3(const NavEKF3 &other) = delete;
42  NavEKF3 &operator=(const NavEKF3&) = delete;
43 
44  static const struct AP_Param::GroupInfo var_info[];
45 
46  // allow logging to determine the number of active cores
47  uint8_t activeCores(void) const {
48  return num_cores;
49  }
50 
51  // Initialise the filter
52  bool InitialiseFilter(void);
53 
54  // Update Filter States - this should be called whenever new IMU data is available
55  void UpdateFilter(void);
56 
57  // check if we should write log messages
58  void check_log_write(void);
59 
60  // Check basic filter health metrics and return a consolidated health status
61  bool healthy(void) const;
62 
63  // returns the index of the primary core
64  // return -1 if no primary core selected
65  int8_t getPrimaryCoreIndex(void) const;
66 
67  // returns the index of the IMU of the primary core
68  // return -1 if no primary core selected
69  int8_t getPrimaryCoreIMUIndex(void) const;
70 
71  // Write the last calculated NE position relative to the reference point (m) for the specified instance.
72  // An out of range instance (eg -1) returns data for the the primary instance
73  // If a calculated solution is not available, use the best available data and return false
74  // If false returned, do not use for flight control
75  bool getPosNE(int8_t instance, Vector2f &posNE) const;
76 
77  // Write the last calculated D position relative to the reference point (m) for the specified instance.
78  // An out of range instance (eg -1) returns data for the the primary instance
79  // If a calculated solution is not available, use the best available data and return false
80  // If false returned, do not use for flight control
81  bool getPosD(int8_t instance, float &posD) const;
82 
83  // return NED velocity in m/s for the specified instance
84  // An out of range instance (eg -1) returns data for the the primary instance
85  void getVelNED(int8_t instance, Vector3f &vel) const;
86 
87  // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s for the specified instance
88  // An out of range instance (eg -1) returns data for the the primary instance
89  // 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
90  // but will always be kinematically consistent with the z component of the EKF position state
91  float getPosDownDerivative(int8_t instance) const;
92 
93  // This returns the specific forces in the NED frame
94  void getAccelNED(Vector3f &accelNED) const;
95 
96  // return body axis gyro bias estimates in rad/sec for the specified instance
97  // An out of range instance (eg -1) returns data for the the primary instance
98  void getGyroBias(int8_t instance, Vector3f &gyroBias) const;
99 
100  // return accelerometer bias estimate in m/s/s
101  // An out of range instance (eg -1) returns data for the the primary instance
102  void getAccelBias(int8_t instance, Vector3f &accelBias) const;
103 
104  // return tilt error convergence metric for the specified instance
105  // An out of range instance (eg -1) returns data for the the primary instance
106  void getTiltError(int8_t instance, float &ang) const;
107 
108  // reset body axis gyro bias estimates
109  void resetGyroBias(void);
110 
111  // Resets the baro so that it reads zero at the current height
112  // Resets the EKF height to zero
113  // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
114  // Returns true if the height datum reset has been performed
115  // If using a range finder for height no reset is performed and it returns false
116  bool resetHeightDatum(void);
117 
118  // Commands the EKF to not use GPS.
119  // This command must be sent prior to vehicle arming and EKF commencement of GPS usage
120  // Returns 0 if command rejected
121  // Returns 1 if command accepted
122  uint8_t setInhibitGPS(void);
123 
124  // Set the argument to true to prevent the EKF using the GPS vertical velocity
125  // This can be used for situations where GPS velocity errors are causing problems with height accuracy
126  void setInhibitGpsVertVelUse(const bool varIn) { inhibitGpsVertVelUse = varIn; };
127 
128  // return the horizontal speed limit in m/s set by optical flow sensor limits
129  // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
130  void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const;
131 
132  // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
133  // An out of range instance (eg -1) returns data for the the primary instance
134  void getWind(int8_t instance, Vector3f &wind) const;
135 
136  // return earth magnetic field estimates in measurement units / 1000 for the specified instance
137  // An out of range instance (eg -1) returns data for the the primary instance
138  void getMagNED(int8_t instance, Vector3f &magNED) const;
139 
140  // return body magnetic field estimates in measurement units / 1000 for the specified instance
141  // An out of range instance (eg -1) returns data for the the primary instance
142  void getMagXYZ(int8_t instance, Vector3f &magXYZ) const;
143 
144  // return the magnetometer in use for the specified instance
145  // An out of range instance (eg -1) returns data for the the primary instance
146  uint8_t getActiveMag(int8_t instance) const;
147 
148  // Return estimated magnetometer offsets
149  // Return true if magnetometer offsets are valid
150  bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;
151 
152  // Return the last calculated latitude, longitude and height in WGS-84
153  // If a calculated location isn't available, return a raw GPS measurement
154  // The status will return true if a calculation or raw measurement is available
155  // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
156  bool getLLH(struct Location &loc) const;
157 
158  // Return the latitude and longitude and height used to set the NED origin for the specified instance
159  // An out of range instance (eg -1) returns data for the the primary instance
160  // All NED positions calculated by the filter are relative to this location
161  // Returns false if the origin has not been set
162  bool getOriginLLH(int8_t instance, struct Location &loc) const;
163 
164  // set the latitude and longitude and height used to set the NED origin
165  // All NED positions calculated by the filter will be relative to this location
166  // The origin cannot be set if the filter is in a flight mode (eg vehicle armed)
167  // Returns false if the filter has rejected the attempt to set the origin
168  bool setOriginLLH(const Location &loc);
169 
170  // return estimated height above ground level
171  // return false if ground height is not being estimated.
172  bool getHAGL(float &HAGL) const;
173 
174  // return the Euler roll, pitch and yaw angle in radians for the specified instance
175  // An out of range instance (eg -1) returns data for the the primary instance
176  void getEulerAngles(int8_t instance, 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(int8_t instance, Quaternion &quat) const;
183 
184  // return the innovations for the specified instance
185  // An out of range instance (eg -1) returns data for the the primary instance
186  void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;
187 
188  // publish output observer angular, velocity and position tracking error
189  void getOutputTrackingError(int8_t instance, Vector3f &error) const;
190 
191  // return the innovation consistency test ratios for the specified instance
192  // An out of range instance (eg -1) returns data for the the primary instance
193  void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const;
194 
195  // return the diagonals from the covariance matrix for the specified instance
196  void getStateVariances(int8_t instance, float stateVar[24]) const;
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  /*
212  * Write body frame linear and angular displacement measurements from a visual odometry sensor
213  *
214  * quality is a normalised confidence value from 0 to 100
215  * delPos is the XYZ change in linear position measured in body frame and relative to the inertial reference at timeStamp_ms (m)
216  * delAng is the XYZ angular rotation measured in body frame and relative to the inertial reference at timeStamp_ms (rad)
217  * delTime is the time interval for the measurement of delPos and delAng (sec)
218  * timeStamp_ms is the timestamp of the last image used to calculate delPos and delAng (msec)
219  * posOffset is the XYZ body frame position of the camera focal point (m)
220  */
221  void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset);
222 
223  /*
224  * Write odometry data from a wheel encoder. The axis of rotation is assumed to be parallel to the vehicle body axis
225  *
226  * 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)
227  * delTime is the time interval for the measurement of delAng (sec)
228  * timeStamp_ms is the time when the rotation was last measured (msec)
229  * posOffset is the XYZ body frame position of the wheel hub (m)
230  * radius is the effective rolling radius of the wheel (m)
231  */
232  void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius);
233 
234  /*
235  * Return data for debugging body frame odometry fusion:
236  *
237  * velInnov are the XYZ body frame velocity innovations (m/s)
238  * velInnovVar are the XYZ body frame velocity innovation variances (m/s)**2
239  *
240  * Return the system time stamp of the last update (msec)
241  */
242  uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const;
243 
244  // return data for debugging optical flow fusion for the specified instance
245  // An out of range instance (eg -1) returns data for the the primary instance
246  void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const;
247 
248  /*
249  Returns the following data for debugging range beacon fusion
250  ID : beacon identifier
251  rng : measured range to beacon (m)
252  innov : range innovation (m)
253  innovVar : innovation variance (m^2)
254  testRatio : innovation consistency test ratio
255  beaconPosNED : beacon NED position (m)
256  offsetHigh : high hypothesis for range beacons system vertical offset (m)
257  offsetLow : low hypothesis for range beacons system vertical offset (m)
258  posNED : North,East,Down position estimate of receiver from 3-state filter
259 
260  returns true if data could be found, false if it could not
261  */
262  bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED,
263  float &offsetHigh, float &offsetLow, Vector3f &posNED) const;
264 
265  // called by vehicle code to specify that a takeoff is happening
266  // causes the EKF to compensate for expected barometer errors due to ground effect
267  void setTakeoffExpected(bool val);
268 
269  // called by vehicle code to specify that a touchdown is expected to happen
270  // causes the EKF to compensate for expected barometer errors due to ground effect
271  void setTouchdownExpected(bool val);
272 
273  // Set to true if the terrain underneath is stable enough to be used as a height reference
274  // in combination with a range finder. Set to false if the terrain underneath the vehicle
275  // cannot be used as a height reference
276  void setTerrainHgtStable(bool val);
277 
278  /*
279  return the filter fault status as a bitmasked integer for the specified instance
280  An out of range instance (eg -1) returns data for the the primary instance
281  0 = quaternions are NaN
282  1 = velocities are NaN
283  2 = badly conditioned X magnetometer fusion
284  3 = badly conditioned Y magnetometer fusion
285  5 = badly conditioned Z magnetometer fusion
286  6 = badly conditioned airspeed fusion
287  7 = badly conditioned synthetic sideslip fusion
288  7 = filter is not initialised
289  */
290  void getFilterFaults(int8_t instance, uint16_t &faults) const;
291 
292  /*
293  return filter timeout status as a bitmasked integer for the specified instance
294  An out of range instance (eg -1) returns data for the the primary instance
295  0 = position measurement timeout
296  1 = velocity measurement timeout
297  2 = height measurement timeout
298  3 = magnetometer measurement timeout
299  5 = unassigned
300  6 = unassigned
301  7 = unassigned
302  7 = unassigned
303  */
304  void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const;
305 
306  /*
307  return filter gps quality check status for the specified instance
308  An out of range instance (eg -1) returns data for the the primary instance
309  */
310  void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const;
311 
312  /*
313  return filter status flags for the specified instance
314  An out of range instance (eg -1) returns data for the the primary instance
315  */
316  void getFilterStatus(int8_t instance, nav_filter_status &status) const;
317 
318  // send an EKF_STATUS_REPORT message to GCS
319  void send_status_report(mavlink_channel_t chan);
320 
321  // provides the height limit to be observed by the control loops
322  // returns false if no height limiting is required
323  // this is needed to ensure the vehicle does not fly too high when using optical flow navigation
324  bool getHeightControlLimit(float &height) const;
325 
326  // return the amount of yaw angle change (in radians) due to the last yaw angle reset or core selection switch
327  // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
328  uint32_t getLastYawResetAngle(float &yawAngDelta);
329 
330  // return the amount of NE position change due to the last position reset in metres
331  // returns the time of the last reset or 0 if no reset has ever occurred
332  uint32_t getLastPosNorthEastReset(Vector2f &posDelta);
333 
334  // return the amount of NE velocity change due to the last velocity reset in metres/sec
335  // returns the time of the last reset or 0 if no reset has ever occurred
336  uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
337 
338  // return the amount of vertical position change due to the last reset in metres
339  // returns the time of the last reset or 0 if no reset has ever occurred
340  uint32_t getLastPosDownReset(float &posDelta);
341 
342  // report any reason for why the backend is refusing to initialise
343  const char *prearm_failure_reason(void) const;
344 
345  // set and save the _baroAltNoise parameter
346  void set_baro_alt_noise(float noise) { _baroAltNoise.set_and_save(noise); };
347 
348  // allow the enable flag to be set by Replay
349  void set_enable(bool enable) { _enable.set(enable); }
350 
351  // are we doing sensor logging inside the EKF?
352  bool have_ekf_logging(void) const { return logging.enabled && _logging_mask != 0; }
353 
354  // get timing statistics structure
355  void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const;
356 
357 private:
358  uint8_t num_cores; // number of allocated cores
359  uint8_t primary; // current primary core
360  NavEKF3_core *core = nullptr;
361  const AP_AHRS *_ahrs;
363 
364  uint32_t _frameTimeUsec; // time per IMU frame
365  uint8_t _framesPerPrediction; // expected number of IMU frames per prediction
366 
367  // EKF Mavlink Tuneable Parameters
368  AP_Int8 _enable; // zero to disable EKF3
369  AP_Float _gpsHorizVelNoise; // GPS horizontal velocity measurement noise : m/s
370  AP_Float _gpsVertVelNoise; // GPS vertical velocity measurement noise : m/s
371  AP_Float _gpsHorizPosNoise; // GPS horizontal position measurement noise m
372  AP_Float _baroAltNoise; // Baro height measurement noise : m
373  AP_Float _magNoise; // magnetometer measurement noise : gauss
374  AP_Float _easNoise; // equivalent airspeed measurement noise : m/s
375  AP_Float _windVelProcessNoise; // wind velocity state process noise : m/s^2
376  AP_Float _wndVarHgtRateScale; // scale factor applied to wind process noise due to height rate
377  AP_Float _magEarthProcessNoise; // Earth magnetic field process noise : gauss/sec
378  AP_Float _magBodyProcessNoise; // Body magnetic field process noise : gauss/sec
379  AP_Float _gyrNoise; // gyro process noise : rad/s
380  AP_Float _accNoise; // accelerometer process noise : m/s^2
381  AP_Float _gyroBiasProcessNoise; // gyro bias state process noise : rad/s
382  AP_Float _accelBiasProcessNoise;// accel bias state process noise : m/s^2
383  AP_Int16 _hgtDelay_ms; // effective average delay of Height measurements relative to inertial measurements (msec)
384  AP_Int8 _fusionModeGPS; // 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity
385  AP_Int16 _gpsVelInnovGate; // Percentage number of standard deviations applied to GPS velocity innovation consistency check
386  AP_Int16 _gpsPosInnovGate; // Percentage number of standard deviations applied to GPS position innovation consistency check
387  AP_Int16 _hgtInnovGate; // Percentage number of standard deviations applied to height innovation consistency check
388  AP_Int16 _magInnovGate; // Percentage number of standard deviations applied to magnetometer innovation consistency check
389  AP_Int16 _tasInnovGate; // Percentage number of standard deviations applied to true airspeed innovation consistency check
390  AP_Int8 _magCal; // Sets activation condition for in-flight magnetometer calibration
391  AP_Int8 _gpsGlitchRadiusMax; // Maximum allowed discrepancy between inertial and GPS Horizontal position before GPS glitch is declared : m
392  AP_Float _flowNoise; // optical flow rate measurement noise
393  AP_Int16 _flowInnovGate; // Percentage number of standard deviations applied to optical flow innovation consistency check
394  AP_Int8 _flowDelay_ms; // effective average delay of optical flow measurements rel to IMU (msec)
395  AP_Int16 _rngInnovGate; // Percentage number of standard deviations applied to range finder innovation consistency check
396  AP_Float _maxFlowRate; // Maximum flow rate magnitude that will be accepted by the filter
397  AP_Int8 _altSource; // Primary alt source during optical flow navigation. 0 = use Baro, 1 = use range finder.
398  AP_Float _rngNoise; // Range finder noise : m
399  AP_Int8 _gpsCheck; // Bitmask controlling which preflight GPS checks are bypassed
400  AP_Int8 _imuMask; // Bitmask of IMUs to instantiate EKF3 for
401  AP_Int16 _gpsCheckScaler; // Percentage increase to be applied to GPS pre-flight accuracy and drift thresholds
402  AP_Float _noaidHorizNoise; // horizontal position measurement noise assumed when synthesised zero position measurements are used to constrain attitude drift : m
403  AP_Int8 _logging_mask; // mask of IMUs to log
404  AP_Float _yawNoise; // magnetic yaw measurement noise : rad
405  AP_Int16 _yawInnovGate; // Percentage number of standard deviations applied to magnetic yaw innovation consistency check
406  AP_Int8 _tauVelPosOutput; // Time constant of output complementary filter : csec (centi-seconds)
407  AP_Int8 _useRngSwHgt; // Maximum valid range of the range finder as a percentage of the maximum range specified by the sensor driver
408  AP_Float _terrGradMax; // Maximum terrain gradient below the vehicle
409  AP_Float _rngBcnNoise; // Range beacon measurement noise (m)
410  AP_Int16 _rngBcnInnovGate; // Percentage number of standard deviations applied to range beacon innovation consistency check
411  AP_Int8 _rngBcnDelay_ms; // effective average delay of range beacon measurements rel to IMU (msec)
412  AP_Float _useRngSwSpd; // Maximum horizontal ground speed to use range finder as the primary height source (m/s)
413  AP_Float _accBiasLim; // Accelerometer bias limit (m/s/s)
414  AP_Int8 _magMask; // Bitmask forcng specific EKF core instances to use simple heading magnetometer fusion.
415  AP_Int8 _originHgtMode; // Bitmask controlling post alignment correction and reporting of the EKF origin height.
416  AP_Float _visOdmVelErrMax; // Observation 1-STD velocity error assumed for visual odometry sensor at lowest reported quality (m/s)
417  AP_Float _visOdmVelErrMin; // Observation 1-STD velocity error assumed for visual odometry sensor at highest reported quality (m/s)
418  AP_Float _wencOdmVelErr; // Observation 1-STD velocity error assumed for wheel odometry sensor (m/s)
419 
420 
421  // Tuning parameters
422  const float gpsNEVelVarAccScale = 0.05f; // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration
423  const float gpsDVelVarAccScale = 0.07f; // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration
424  const float gpsPosVarAccScale = 0.05f; // Scale factor applied to horizontal position measurement variance due to manoeuvre acceleration
425  const uint16_t magDelay_ms = 60; // Magnetometer measurement delay (msec)
426  const uint16_t tasDelay_ms = 100; // Airspeed measurement delay (msec)
427  const uint16_t tiltDriftTimeMax_ms = 15000; // Maximum number of ms allowed without any form of tilt aiding (GPS, flow, TAS, etc)
428  const uint16_t posRetryTimeUseVel_ms = 10000; // Position aiding retry time with velocity measurements (msec)
429  const uint16_t posRetryTimeNoVel_ms = 7000; // Position aiding retry time without velocity measurements (msec)
430  const uint16_t hgtRetryTimeMode0_ms = 10000; // Height retry time with vertical velocity measurement (msec)
431  const uint16_t hgtRetryTimeMode12_ms = 5000; // Height retry time without vertical velocity measurement (msec)
432  const uint16_t tasRetryTime_ms = 5000; // True airspeed timeout and retry interval (msec)
433  const uint32_t magFailTimeLimit_ms = 10000; // number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
434  const float magVarRateScale = 0.005f; // scale factor applied to magnetometer variance due to angular rate
435  const float gyroBiasNoiseScaler = 2.0f; // scale factor applied to gyro bias state process noise when on ground
436  const uint16_t hgtAvg_ms = 100; // average number of msec between height measurements
437  const uint16_t betaAvg_ms = 100; // average number of msec between synthetic sideslip measurements
438  const float covTimeStepMax = 0.1f; // maximum time (sec) between covariance prediction updates
439  const float covDelAngMax = 0.05f; // maximum delta angle between covariance prediction updates
440  const float DCM33FlowMin = 0.71f; // If Tbn(3,3) is less than this number, optical flow measurements will not be fused as tilt is too high.
441  const float fScaleFactorPnoise = 1e-10f; // Process noise added to focal length scale factor state variance at each time step
442  const uint8_t flowTimeDeltaAvg_ms = 100; // average interval between optical flow measurements (msec)
443  const uint32_t flowIntervalMax_ms = 100; // maximum allowable time between flow fusion events
444  const uint16_t gndEffectTimeout_ms = 1000; // time in msec that ground effect mode is active after being activated
445  const float gndEffectBaroScaler = 4.0f; // scaler applied to the barometer observation variance when ground effect mode is active
446  const uint8_t gndGradientSigma = 50; // RMS terrain gradient percentage assumed by the terrain height estimation
447  const uint16_t fusionTimeStep_ms = 10; // The minimum time interval between covariance predictions and measurement fusions in msec
448  const uint8_t sensorIntervalMin_ms = 50; // The minimum allowed time between measurements from any non-IMU sensor (msec)
449 
450  struct {
451  bool enabled:1;
452  bool log_compass:1;
453  bool log_gps:1;
454  bool log_baro:1;
455  bool log_imu:1;
456  } logging;
457 
458  // time at start of current filter update
460 
461  struct {
462  uint32_t last_function_call; // last time getLastYawYawResetAngle was called
463  bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
464  uint32_t last_primary_change; // last time a primary has changed
465  float core_delta; // the amount of yaw change between cores when a change happened
466  } yaw_reset_data;
467 
468  struct {
469  uint32_t last_function_call; // last time getLastPosNorthEastReset was called
470  bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
471  uint32_t last_primary_change; // last time a primary has changed
472  Vector2f core_delta; // the amount of NE position change between cores when a change happened
473  } pos_reset_data;
474 
475  struct {
476  uint32_t last_function_call; // last time getLastPosDownReset was called
477  bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
478  uint32_t last_primary_change; // last time a primary has changed
479  float core_delta; // the amount of D position change between cores when a change happened
481 
482  bool runCoreSelection; // true when the primary core has stabilised and the core selection logic can be started
483  bool coreSetupRequired[7]; // true when this core index needs to be setup
484  uint8_t coreImuIndex[7]; // IMU index used by this core
485 
486  bool inhibitGpsVertVelUse; // true when GPS vertical velocity use is prohibited
487 
488  // update the yaw reset data to capture changes due to a lane switch
489  // new_primary - index of the ekf instance that we are about to switch to as the primary
490  // old_primary - index of the ekf instance that we are currently using as the primary
491  void updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary);
492 
493  // update the position reset data to capture changes due to a lane switch
494  // new_primary - index of the ekf instance that we are about to switch to as the primary
495  // old_primary - index of the ekf instance that we are currently using as the primary
496  void updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary);
497 
498  // update the position down reset data to capture changes due to a lane switch
499  // new_primary - index of the ekf instance that we are about to switch to as the primary
500  // old_primary - index of the ekf instance that we are currently using as the primary
501  void updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary);
502 };
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
AP_Int16 _hgtDelay_ms
Definition: AP_NavEKF3.h:383
AP_Int8 _gpsGlitchRadiusMax
Definition: AP_NavEKF3.h:391
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
void getTiltError(int8_t instance, float &ang) const
Definition: AP_NavEKF3.cpp:887
AP_Int8 _gpsCheck
Definition: AP_NavEKF3.h:399
AP_Float _magEarthProcessNoise
Definition: AP_NavEKF3.h:377
uint32_t last_function_call
Definition: AP_NavEKF3.h:462
AP_Float _yawNoise
Definition: AP_NavEKF3.h:404
AP_Int8 _originHgtMode
Definition: AP_NavEKF3.h:415
AP_Int16 _hgtInnovGate
Definition: AP_NavEKF3.h:387
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF3.h:384
AP_Float _wencOdmVelErr
Definition: AP_NavEKF3.h:418
bool resetHeightDatum(void)
Definition: AP_NavEKF3.cpp:910
const uint16_t tasRetryTime_ms
Definition: AP_NavEKF3.h:432
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED) const
struct NavEKF3::@148 logging
AP_Int16 _gpsVelInnovGate
Definition: AP_NavEKF3.h:385
AP_Int8 _logging_mask
Definition: AP_NavEKF3.h:403
AP_Int8 _magMask
Definition: AP_NavEKF3.h:414
void send_status_report(mavlink_channel_t chan)
struct NavEKF3::@151 pos_down_reset_data
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_NavEKF3.h:44
void set_enable(bool enable)
Definition: AP_NavEKF3.h:349
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
bool log_baro
Definition: AP_NavEKF3.h:454
AP_Int16 _flowInnovGate
Definition: AP_NavEKF3.h:393
bool log_compass
Definition: AP_NavEKF3.h:452
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
bool setOriginLLH(const Location &loc)
uint8_t num_cores
Definition: AP_NavEKF3.h:358
struct NavEKF3::@150 pos_reset_data
AP_Int8 _enable
Definition: AP_NavEKF3.h:368
AP_Float _wndVarHgtRateScale
Definition: AP_NavEKF3.h:376
uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
AP_Float _baroAltNoise
Definition: AP_NavEKF3.h:372
struct NavEKF3::@149 yaw_reset_data
void set_baro_alt_noise(float noise)
Definition: AP_NavEKF3.h:346
AP_Float _terrGradMax
Definition: AP_NavEKF3.h:408
AP_Int16 _rngBcnInnovGate
Definition: AP_NavEKF3.h:410
AP_Float _easNoise
Definition: AP_NavEKF3.h:374
bool use_compass(void) const
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
Definition: AP_NavEKF3.cpp:869
const RangeFinder & _rng
Definition: AP_NavEKF3.h:362
void getFilterStatus(int8_t instance, nav_filter_status &status) const
AP_Float _gpsHorizPosNoise
Definition: AP_NavEKF3.h:371
const char * prearm_failure_reason(void) const
bool have_ekf_logging(void) const
Definition: AP_NavEKF3.h:352
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
Definition: AP_NavEKF3.cpp:965
AP_Float _noaidHorizNoise
Definition: AP_NavEKF3.h:402
bool getHeightControlLimit(float &height) const
const uint16_t tasDelay_ms
Definition: AP_NavEKF3.h:426
bool InitialiseFilter(void)
Definition: AP_NavEKF3.cpp:620
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
const uint8_t gndGradientSigma
Definition: AP_NavEKF3.h:446
AP_Float _magNoise
Definition: AP_NavEKF3.h:373
ptrdiff_t offset
Definition: AP_Param.h:149
void resetGyroBias(void)
Definition: AP_NavEKF3.cpp:896
uint32_t _frameTimeUsec
Definition: AP_NavEKF3.h:364
AP_Int16 _rngInnovGate
Definition: AP_NavEKF3.h:395
AP_Float _visOdmVelErrMin
Definition: AP_NavEKF3.h:417
uint8_t activeCores(void) const
Definition: AP_NavEKF3.h:47
void setTerrainHgtStable(bool val)
AP_Int16 _magInnovGate
Definition: AP_NavEKF3.h:388
const uint8_t flowTimeDeltaAvg_ms
Definition: AP_NavEKF3.h:442
AP_Int8 _altSource
Definition: AP_NavEKF3.h:397
const uint16_t hgtAvg_ms
Definition: AP_NavEKF3.h:436
void getRotationBodyToNED(Matrix3f &mat) const
const uint8_t sensorIntervalMin_ms
Definition: AP_NavEKF3.h:448
void setTouchdownExpected(bool val)
A system for managing and storing variables that are of general interest to the system.
void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
uint32_t last_primary_change
Definition: AP_NavEKF3.h:464
Vector2f core_delta
Definition: AP_NavEKF3.h:472
void updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
uint32_t getLastYawResetAngle(float &yawAngDelta)
NavEKF3 & operator=(const NavEKF3 &)=delete
void setTakeoffExpected(bool val)
bool inhibitGpsVertVelUse
Definition: AP_NavEKF3.h:486
AP_Float _maxFlowRate
Definition: AP_NavEKF3.h:396
bool getLLH(struct Location &loc) const
NavEKF3_core * core
Definition: AP_NavEKF3.h:360
AP_Float _windVelProcessNoise
Definition: AP_NavEKF3.h:375
void updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
void getVelNED(int8_t instance, Vector3f &vel) const
Definition: AP_NavEKF3.cpp:841
bool enabled
Definition: AP_NavEKF3.h:451
uint8_t primary
Definition: AP_NavEKF3.h:359
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
AP_Float _magBodyProcessNoise
Definition: AP_NavEKF3.h:378
#define f(i)
const uint16_t hgtRetryTimeMode0_ms
Definition: AP_NavEKF3.h:430
const float DCM33FlowMin
Definition: AP_NavEKF3.h:440
bool getPosD(int8_t instance, float &posD) const
Definition: AP_NavEKF3.cpp:831
AP_Int8 _magCal
Definition: AP_NavEKF3.h:390
int8_t getPrimaryCoreIMUIndex(void) const
Definition: AP_NavEKF3.cpp:808
AP_Int16 _yawInnovGate
Definition: AP_NavEKF3.h:405
AP_Int16 _gpsPosInnovGate
Definition: AP_NavEKF3.h:386
void getEulerAngles(int8_t instance, Vector3f &eulers) const
const uint16_t hgtRetryTimeMode12_ms
Definition: AP_NavEKF3.h:431
AP_Int16 _tasInnovGate
Definition: AP_NavEKF3.h:389
void check_log_write(void)
Definition: AP_NavEKF3.cpp:592
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
const float gpsPosVarAccScale
Definition: AP_NavEKF3.h:424
void UpdateFilter(void)
Definition: AP_NavEKF3.cpp:720
uint64_t imuSampleTime_us
Definition: AP_NavEKF3.h:459
void getFilterFaults(int8_t instance, uint16_t &faults) const
const uint16_t betaAvg_ms
Definition: AP_NavEKF3.h:437
AP_Float _visOdmVelErrMax
Definition: AP_NavEKF3.h:416
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
Definition: AP_NavEKF3.cpp:986
uint32_t getLastPosDownReset(float &posDelta)
AP_Float _rngNoise
Definition: AP_NavEKF3.h:398
float core_delta
Definition: AP_NavEKF3.h:465
NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng)
Definition: AP_NavEKF3.cpp:582
const float covTimeStepMax
Definition: AP_NavEKF3.h:438
AP_Int8 _imuMask
Definition: AP_NavEKF3.h:400
bool coreSetupRequired[7]
Definition: AP_NavEKF3.h:483
const uint32_t magFailTimeLimit_ms
Definition: AP_NavEKF3.h:433
const float fScaleFactorPnoise
Definition: AP_NavEKF3.h:441
const uint16_t magDelay_ms
Definition: AP_NavEKF3.h:425
bool getHAGL(float &HAGL) const
AP_Float _accBiasLim
Definition: AP_NavEKF3.h:413
bool log_imu
Definition: AP_NavEKF3.h:455
void getMagNED(int8_t instance, Vector3f &magNED) const
Definition: AP_NavEKF3.cpp:956
uint8_t coreImuIndex[7]
Definition: AP_NavEKF3.h:484
bool getPosNE(int8_t instance, Vector2f &posNE) const
Definition: AP_NavEKF3.cpp:819
void setInhibitGpsVertVelUse(const bool varIn)
Definition: AP_NavEKF3.h:126
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
void getQuaternion(int8_t instance, Quaternion &quat) const
int8_t getPrimaryCoreIndex(void) const
Definition: AP_NavEKF3.cpp:798
const float gndEffectBaroScaler
Definition: AP_NavEKF3.h:445
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
AP_Int8 _flowDelay_ms
Definition: AP_NavEKF3.h:394
bool healthy(void) const
Definition: AP_NavEKF3.cpp:788
AP_Float _flowNoise
Definition: AP_NavEKF3.h:392
bool getOriginLLH(int8_t instance, struct Location &loc) const
bool core_changed
Definition: AP_NavEKF3.h:463
const uint16_t fusionTimeStep_ms
Definition: AP_NavEKF3.h:447
uint8_t setInhibitGPS(void)
Definition: AP_NavEKF3.cpp:929
#define error(fmt, args ...)
const float magVarRateScale
Definition: AP_NavEKF3.h:434
AP_Int8 _tauVelPosOutput
Definition: AP_NavEKF3.h:406
const uint32_t flowIntervalMax_ms
Definition: AP_NavEKF3.h:443
AP_Float _useRngSwSpd
Definition: AP_NavEKF3.h:412
const uint16_t posRetryTimeNoVel_ms
Definition: AP_NavEKF3.h:429
const uint16_t gndEffectTimeout_ms
Definition: AP_NavEKF3.h:444
void getStateVariances(int8_t instance, float stateVar[24]) const
bool log_gps
Definition: AP_NavEKF3.h:453
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
Definition: AP_NavEKF3.cpp:939
AP_Int8 _rngBcnDelay_ms
Definition: AP_NavEKF3.h:411
AP_Float _accelBiasProcessNoise
Definition: AP_NavEKF3.h:382
float getPosDownDerivative(int8_t instance) const
Definition: AP_NavEKF3.cpp:850
AP_Float _gpsVertVelNoise
Definition: AP_NavEKF3.h:370
const uint16_t tiltDriftTimeMax_ms
Definition: AP_NavEKF3.h:427
AP_Float _gyrNoise
Definition: AP_NavEKF3.h:379
Catch-all header that defines all supported RangeFinder classes.
void getAccelBias(int8_t instance, Vector3f &accelBias) const
Definition: AP_NavEKF3.cpp:878
void getWind(int8_t instance, Vector3f &wind) const
Definition: AP_NavEKF3.cpp:947
uint8_t _framesPerPrediction
Definition: AP_NavEKF3.h:365
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
const uint16_t posRetryTimeUseVel_ms
Definition: AP_NavEKF3.h:428
void getOutputTrackingError(int8_t instance, Vector3f &error) const
AP_Float _gyroBiasProcessNoise
Definition: AP_NavEKF3.h:381
bool runCoreSelection
Definition: AP_NavEKF3.h:482
static float noise(void)
Definition: Derivative.cpp:21
const float gyroBiasNoiseScaler
Definition: AP_NavEKF3.h:435
const float gpsDVelVarAccScale
Definition: AP_NavEKF3.h:423
const float covDelAngMax
Definition: AP_NavEKF3.h:439
const float gpsNEVelVarAccScale
Definition: AP_NavEKF3.h:422
AP_Int8 _useRngSwHgt
Definition: AP_NavEKF3.h:407
uint8_t getActiveMag(int8_t instance) const
Definition: AP_NavEKF3.cpp:974
AP_Float _rngBcnNoise
Definition: AP_NavEKF3.h:409
AP_Int16 _gpsCheckScaler
Definition: AP_NavEKF3.h:401
AP_Float _gpsHorizVelNoise
Definition: AP_NavEKF3.h:369
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
const AP_AHRS * _ahrs
Definition: AP_NavEKF3.h:361
void updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
void getAccelNED(Vector3f &accelNED) const
Definition: AP_NavEKF3.cpp:861
AP_Float _accNoise
Definition: AP_NavEKF3.h:380