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