AP_NavEKF3: Allow reporting of airspeed consistency for a deselected sensor
[ardupilot.git] / libraries / AP_NavEKF3 / AP_NavEKF3_core.h
blob13250a71ec82af412efc36945866470a1e6892c1
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
5 Converted from Matlab to C++ by Paul Riseborough
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.
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.
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/>.
20 #pragma once
23 #if !defined(HAL_DEBUG_BUILD) || !HAL_DEBUG_BUILD
24 #pragma GCC optimize("O2")
25 #endif
27 #include "AP_NavEKF3_feature.h"
28 #include <AP_Common/Location.h>
29 #include <AP_Math/AP_Math.h>
30 #include <AP_Math/vectorN.h>
31 #include <AP_NavEKF/AP_NavEKF_core_common.h>
32 #include <AP_NavEKF/AP_NavEKF_Source.h>
33 #include <AP_NavEKF/EKF_Buffer.h>
34 #include <AP_InertialSensor/AP_InertialSensor.h>
35 #include <AP_DAL/AP_DAL.h>
37 #include "AP_NavEKF/EKFGSF_yaw.h"
39 // GPS pre-flight check bit locations
40 #define MASK_GPS_NSATS (1<<0)
41 #define MASK_GPS_HDOP (1<<1)
42 #define MASK_GPS_SPD_ERR (1<<2)
43 #define MASK_GPS_POS_ERR (1<<3)
44 #define MASK_GPS_YAW_ERR (1<<4)
45 #define MASK_GPS_POS_DRIFT (1<<5)
46 #define MASK_GPS_VERT_SPD (1<<6)
47 #define MASK_GPS_HORIZ_SPD (1<<7)
49 #define earthRate 0.000072921f // earth rotation rate (rad/sec)
51 // maximum allowed gyro bias (rad/sec)
52 #define GYRO_BIAS_LIMIT 0.5f
54 // initial accel bias uncertainty as a fraction of the state limit
55 #define ACCEL_BIAS_LIM_SCALER 0.2f
57 // target update time for the EKF in msec and sec
58 #define EKF_TARGET_DT_MS 12
59 #define EKF_TARGET_DT 0.012f
61 // mag fusion final reset altitude (using NED frame so altitude is negative)
62 #define EKF3_MAG_FINAL_RESET_ALT 2.5f
64 // learning rate for mag biases when using GPS yaw
65 #define EK3_GPS_MAG_LEARN_RATE 0.005f
67 // learning limit for mag biases when using GPS yaw (Gauss)
68 #define EK3_GPS_MAG_LEARN_LIMIT 0.02f
70 // maximum number of yaw resets due to detected magnetic anomaly allowed per flight
71 #define MAG_ANOMALY_RESET_MAX 2
73 // number of seconds a request to reset the yaw to the GSF estimate is active before it times out
74 #define YAW_RESET_TO_GSF_TIMEOUT_MS 5000
76 // accuracy threshold applied to GSF yaw estimate use
77 #define GSF_YAW_ACCURACY_THRESHOLD_DEG 15.0f
79 // number of continuous valid GSF yaw estimates required to confirm valid hostory
80 #define GSF_YAW_VALID_HISTORY_THRESHOLD 5
82 // minimum variances allowed for velocity and position states
83 #define VEL_STATE_MIN_VARIANCE 1E-4
84 #define POS_STATE_MIN_VARIANCE 1E-4
86 // maximum number of times the vertical velocity variance can hit the lower limit before the
87 // associated states, variances and covariances are reset
88 #define EKF_TARGET_RATE_HZ uint32_t(1.0 / EKF_TARGET_DT)
89 #define VERT_VEL_VAR_CLIP_COUNT_LIM (5 * EKF_TARGET_RATE_HZ)
91 // limit on horizontal position states
92 #if HAL_WITH_EKF_DOUBLE
93 #define EK3_POSXY_STATE_LIMIT 50.0e6
94 #else
95 #define EK3_POSXY_STATE_LIMIT 1.0e6
96 #endif
98 // IMU acceleration process noise in m/s/s used when bad vibration affected IMU accel is detected
99 #define BAD_IMU_DATA_ACC_P_NSE 5.0f
101 // Number of milliseconds of bad IMU data before a reset to vertical position and velocity height sources is performed
102 #define BAD_IMU_DATA_TIMEOUT_MS 1000
104 // number of milliseconds the bad IMU data response settings will be held after the last bad IMU data is detected
105 #define BAD_IMU_DATA_HOLD_MS 10000
107 // wind state variance limits
108 #define WIND_VEL_VARIANCE_MAX 400.0f
109 #define WIND_VEL_VARIANCE_MIN 0.25f
112 class NavEKF3_core : public NavEKF_core_common
114 public:
115 // Constructor
116 NavEKF3_core(class NavEKF3 *_frontend);
118 // setup this core backend
119 bool setup_core(uint8_t _imu_index, uint8_t _core_index);
121 // Initialise the states from accelerometer and magnetometer data (if present)
122 // This method can only be used when the vehicle is static
123 bool InitialiseFilterBootstrap(void);
125 // Update Filter States - this should be called whenever new IMU data is available
126 // The predict flag is set true when a new prediction cycle can be started
127 void UpdateFilter(bool predict);
129 // Check basic filter health metrics and return a consolidated health status
130 bool healthy(void) const;
132 // Return a consolidated error score where higher numbers are less healthy
133 // Intended to be used by the front-end to determine which is the primary EKF
134 float errorScore(void) const;
136 // Write the last calculated NE position relative to the reference point (m).
137 // If a calculated solution is not available, use the best available data and return false
138 // If false returned, do not use for flight control
139 bool getPosNE(Vector2f &posNE) const;
141 // Write the last calculated D position relative to the reference point (m).
142 // If a calculated solution is not available, use the best available data and return false
143 // If false returned, do not use for flight control
144 bool getPosD(float &posD) const;
146 // return NED velocity in m/s
147 void getVelNED(Vector3f &vel) const;
149 // return estimate of true airspeed vector in body frame in m/s
150 // returns false if estimate is unavailable
151 bool getAirSpdVec(Vector3f &vel) const;
153 // return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed
154 // returns false if the data is unavailable
155 bool getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const;
157 // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
158 // 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
159 // but will always be kinematically consistent with the z component of the EKF position state
160 float getPosDownDerivative(void) const;
162 // return body axis gyro bias estimates in rad/sec
163 void getGyroBias(Vector3f &gyroBias) const;
165 // return accelerometer bias in m/s/s
166 void getAccelBias(Vector3f &accelBias) const;
168 // reset body axis gyro bias estimates
169 void resetGyroBias(void);
171 // Resets the baro so that it reads zero at the current height
172 // Resets the EKF height to zero
173 // Adjusts the EKF origin height so that the EKF height + origin height is the same as before
174 // Returns true if the height datum reset has been performed
175 // If using a range finder for height no reset is performed and it returns false
176 bool resetHeightDatum(void);
178 // return the horizontal speed limit in m/s set by optical flow sensor limits
179 // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
180 void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const;
182 // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
183 // returns true if wind state estimation is active
184 bool getWind(Vector3f &wind) const;
186 // return earth magnetic field estimates in measurement units / 1000
187 void getMagNED(Vector3f &magNED) const;
189 // return body magnetic field estimates in measurement units / 1000
190 void getMagXYZ(Vector3f &magXYZ) const;
192 // return the index for the active sensors
193 uint8_t getActiveAirspeed() const;
195 // Return estimated magnetometer offsets
196 // Return true if magnetometer offsets are valid
197 bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;
199 // Return the last calculated latitude, longitude and height in WGS-84
200 // If a calculated location isn't available, return a raw GPS measurement
201 // The status will return true if a calculation or raw measurement is available
202 // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
203 bool getLLH(struct Location &loc) const;
205 // return the latitude and longitude and height used to set the NED origin
206 // All NED positions calculated by the filter are relative to this location
207 // Returns false if the origin has not been set
208 bool getOriginLLH(struct Location &loc) const;
210 // set the latitude and longitude and height used to set the NED origin
211 // All NED positions calculated by the filter will be relative to this location
212 // returns false if Absolute aiding and GPS is being used or if the origin is already set
213 bool setOriginLLH(const Location &loc);
215 // return estimated height above ground level
216 // return false if ground height is not being estimated.
217 bool getHAGL(float &HAGL) const;
219 // return the Euler roll, pitch and yaw angle in radians
220 void getEulerAngles(Vector3f &eulers) const;
222 // return the transformation matrix from XYZ (body) to NED axes
223 void getRotationBodyToNED(Matrix3f &mat) const;
225 // return the quaternions defining the rotation from NED to XYZ (body) axes
226 void getQuaternion(Quaternion &quat) const;
228 // return the innovations for the NED Pos, NED Vel, XYZ Mag and Vtas measurements
229 bool getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;
231 // return the synthetic air data drag and sideslip innovations
232 void getSynthAirDataInnovations(Vector2f &dragInnov, float &betaInnov) const;
234 // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements
235 bool getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const;
237 // get a particular source's velocity innovations
238 // returns true on success and results are placed in innovations and variances arguments
239 bool getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::SourceXY source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED;
241 // should we use the compass? This is public so it can be used for
242 // reporting via ahrs.use_compass()
243 bool use_compass(void) const;
245 // write the raw optical flow measurements
246 // rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality
247 // rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes.
248 // rawGyroRates are the sensor rotation rates in rad/sec measured by the sensors internal gyro
249 // The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
250 // msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
251 // posOffset is the XYZ flow sensor position in the body frame in m
252 void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset);
254 // retrieve latest corrected optical flow samples (used for calibration)
255 bool getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const;
258 * Write body frame linear and angular displacement measurements from a visual odometry sensor
260 * quality is a normalised confidence value from 0 to 100
261 * delPos is the XYZ change in linear position measured in body frame and relative to the inertial reference at time_ms (m)
262 * delAng is the XYZ angular rotation measured in body frame and relative to the inertial reference at time_ms (rad)
263 * delTime is the time interval for the measurement of delPos and delAng (sec)
264 * timeStamp_ms is the timestamp of the last image used to calculate delPos and delAng (msec)
265 * delay_ms is the average delay of external nav system measurements relative to inertial measurements
266 * posOffset is the XYZ body frame position of the camera focal point (m)
268 void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset);
271 * Write odometry data from a wheel encoder. The axis of rotation is assumed to be parallel to the vehicle body axis
273 * 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)
274 * delTime is the time interval for the measurement of delAng (sec)
275 * timeStamp_ms is the time when the rotation was last measured (msec)
276 * posOffset is the XYZ body frame position of the wheel hub (m)
277 * radius is the effective rolling radius of the wheel (m)
279 void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius);
282 * Return data for debugging body frame odometry fusion:
284 * velInnov are the XYZ body frame velocity innovations (m/s)
285 * velInnovVar are the XYZ body frame velocity innovation variances (m/s)**2
287 * Return the time stamp of the last odometry fusion update (msec)
289 uint32_t getBodyFrameOdomDebug(Vector3f &velInnov, Vector3f &velInnovVar);
292 * Writes the measurement from a yaw angle sensor
294 * yawAngle: Yaw angle of the vehicle relative to true north in radians where a positive angle is
295 * produced by a RH rotation about the Z body axis. The Yaw rotation is the first rotation in a
296 * 321 (ZYX) or a 312 (ZXY) rotation sequence as specified by the 'type' argument.
297 * yawAngleErr is the 1SD accuracy of the yaw angle measurement in radians.
298 * timeStamp_ms: System time in msec when the yaw measurement was taken. This time stamp must include
299 * all measurement lag and transmission delays.
300 * type: An integer specifying Euler rotation order used to define the yaw angle.
301 * type = 1 specifies a 312 (ZXY) rotation order, type = 2 specifies a 321 (ZYX) rotation order.
303 void writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type);
306 * Write position and quaternion data from an external navigation system
308 * pos : position in the RH navigation frame. Frame is assumed to be NED if frameIsNED is true. (m)
309 * quat : quaternion desribing the rotation from navigation frame to body frame
310 * posErr : 1-sigma spherical position error (m)
311 * angErr : 1-sigma spherical angle error (rad)
312 * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
313 * delay_ms : average delay of external nav system measurements relative to inertial measurements
314 * resetTime_ms : system time of the last position reset request (mSec)
317 void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms);
320 * Write velocity data from an external navigation system
322 * vel : velocity in NED (m)
323 * err : velocity error (m/s)
324 * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
325 * delay_ms : average delay of external nav system measurements relative to inertial measurements
327 void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);
329 // Set to true if the terrain underneath is stable enough to be used as a height reference
330 // in combination with a range finder. Set to false if the terrain underneath the vehicle
331 // cannot be used as a height reference. Use to prevent range finder operation otherwise
332 // enabled by the combination of EK3_RNG_USE_HGT and EK3_RNG_USE_SPD parameters.
333 void setTerrainHgtStable(bool val);
336 return the filter fault status as a bitmasked integer
337 0 = quaternions are NaN
338 1 = velocities are NaN
339 2 = badly conditioned X magnetometer fusion
340 3 = badly conditioned Y magnetometer fusion
341 5 = badly conditioned Z magnetometer fusion
342 6 = badly conditioned airspeed fusion
343 7 = badly conditioned synthetic sideslip fusion
344 7 = filter is not initialised
346 void getFilterFaults(uint16_t &faults) const;
349 Return a filter function status that indicates:
350 Which outputs are valid
351 If the filter has detected takeoff
352 If the filter has activated the mode that mitigates against ground effect static pressure errors
353 If GPS data is being used
355 void getFilterStatus(nav_filter_status &status) const;
357 // send an EKF_STATUS_REPORT message to GCS
358 void send_status_report(class GCS_MAVLINK &link) const;
360 // provides the height limit to be observed by the control loops
361 // returns false if no height limiting is required
362 // this is needed to ensure the vehicle does not fly too high when using optical flow navigation
363 bool getHeightControlLimit(float &height) const;
365 // return the amount of yaw angle change due to the last yaw angle reset in radians
366 // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
367 uint32_t getLastYawResetAngle(float &yawAng) const;
369 // return the amount of NE position change due to the last position reset in metres
370 // returns the time of the last reset or 0 if no reset has ever occurred
371 uint32_t getLastPosNorthEastReset(Vector2f &pos) const;
373 // return the amount of D position change due to the last position reset in metres
374 // returns the time of the last reset or 0 if no reset has ever occurred
375 uint32_t getLastPosDownReset(float &posD) const;
377 // return the amount of NE velocity change due to the last velocity reset in metres/sec
378 // returns the time of the last reset or 0 if no reset has ever occurred
379 uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
381 // report any reason for why the backend is refusing to initialise
382 const char *prearm_failure_reason(void) const;
384 // report the number of frames lapsed since the last state prediction
385 // this is used by other instances to level load
386 uint8_t getFramesSincePredict(void) const;
388 // get the IMU index. For now we return the gyro index, as that is most
389 // critical for use by other subsystems.
390 uint8_t getIMUIndex(void) const { return gyro_index_active; }
392 // values for EK3_MAG_CAL
393 enum class MagCal {
394 WHEN_FLYING = 0,
395 WHEN_MANOEUVRING = 1,
396 NEVER = 2,
397 AFTER_FIRST_CLIMB = 3,
398 ALWAYS = 4
399 // 5 was EXTERNAL_YAW (do not use)
400 // 6 was EXTERNAL_YAW_FALLBACK (do not use)
403 // are we using (aka fusing) a non-compass yaw?
404 bool using_noncompass_for_yaw(void) const;
406 // are we using (aka fusing) external nav for yaw?
407 bool using_extnav_for_yaw() const;
409 // Writes the default equivalent airspeed and 1-sigma uncertainty in m/s to be used in forward flight if a measured airspeed is required and not available.
410 void writeDefaultAirSpeed(float airspeed, float uncertainty);
412 // request a reset the yaw to the EKF-GSF value
413 void EKFGSF_requestYawReset();
415 // return true if we are tilt aligned
416 bool have_aligned_tilt(void) const {
417 return tiltAlignComplete;
420 // return true if we are yaw aligned
421 bool have_aligned_yaw(void) const {
422 return yawAlignComplete;
425 void Log_Write(uint64_t time_us);
427 // returns true when the state estimates are significantly degraded by vibration
428 bool isVibrationAffected() const { return badIMUdata; }
430 // get a yaw estimator instance
431 const EKFGSF_yaw *get_yawEstimator(void) const { return yawEstimator; }
433 private:
434 EKFGSF_yaw *yawEstimator;
435 AP_DAL &dal;
437 // Reference to the global EKF frontend for parameters
438 class NavEKF3 *frontend;
439 uint8_t imu_index; // preferred IMU index
440 uint8_t gyro_index_active; // active gyro index (in case preferred fails)
441 uint8_t accel_index_active; // active accel index (in case preferred fails)
442 uint8_t core_index;
443 uint8_t imu_buffer_length;
444 uint8_t obs_buffer_length;
446 #if MATH_CHECK_INDEXES
447 typedef VectorN<ftype,2> Vector2;
448 typedef VectorN<ftype,3> Vector3;
449 typedef VectorN<ftype,4> Vector4;
450 typedef VectorN<ftype,5> Vector5;
451 typedef VectorN<ftype,6> Vector6;
452 typedef VectorN<ftype,7> Vector7;
453 typedef VectorN<ftype,8> Vector8;
454 typedef VectorN<ftype,9> Vector9;
455 typedef VectorN<ftype,10> Vector10;
456 typedef VectorN<ftype,11> Vector11;
457 typedef VectorN<ftype,13> Vector13;
458 typedef VectorN<ftype,14> Vector14;
459 typedef VectorN<ftype,15> Vector15;
460 typedef VectorN<ftype,21> Vector21;
461 typedef VectorN<ftype,22> Vector22;
462 typedef VectorN<ftype,23> Vector23;
463 typedef VectorN<ftype,24> Vector24;
464 typedef VectorN<ftype,25> Vector25;
465 typedef VectorN<ftype,31> Vector31;
466 typedef VectorN<VectorN<ftype,3>,3> Matrix3;
467 typedef VectorN<VectorN<ftype,24>,24> Matrix24;
468 typedef VectorN<VectorN<ftype,34>,50> Matrix34_50;
469 typedef VectorN<uint32_t,50> Vector_u32_50;
470 #else
471 typedef ftype Vector2[2];
472 typedef ftype Vector3[3];
473 typedef ftype Vector4[4];
474 typedef ftype Vector5[5];
475 typedef ftype Vector6[6];
476 typedef ftype Vector7[7];
477 typedef ftype Vector8[8];
478 typedef ftype Vector9[9];
479 typedef ftype Vector10[10];
480 typedef ftype Vector11[11];
481 typedef ftype Vector13[13];
482 typedef ftype Vector14[14];
483 typedef ftype Vector15[15];
484 typedef ftype Vector21[21];
485 typedef ftype Vector22[22];
486 typedef ftype Vector23[23];
487 typedef ftype Vector24[24];
488 typedef ftype Vector25[25];
489 typedef ftype Matrix3[3][3];
490 typedef ftype Matrix24[24][24];
491 typedef ftype Matrix34_50[34][50];
492 typedef uint32_t Vector_u32_50[50];
493 #endif
495 // the states are available in two forms, either as a Vector24, or
496 // broken down as individual elements. Both are equivalent (same
497 // memory)
498 struct state_elements {
499 QuaternionF quat; // quaternion defining rotation from local NED earth frame to body frame 0..3
500 Vector3F velocity; // velocity of IMU in local NED earth frame (m/sec) 4..6
501 Vector3F position; // position of IMU in local NED earth frame (m) 7..9
502 Vector3F gyro_bias; // body frame delta angle IMU bias vector (rad) 10..12
503 Vector3F accel_bias; // body frame delta velocity IMU bias vector (m/sec) 13..15
504 Vector3F earth_magfield; // earth frame magnetic field vector (Gauss) 16..18
505 Vector3F body_magfield; // body frame magnetic field vector (Gauss) 19..21
506 Vector2F wind_vel; // horizontal North East wind velocity vector in local NED earth frame (m/sec) 22..23
509 union {
510 Vector24 statesArray;
511 struct state_elements stateStruct;
514 struct output_elements {
515 QuaternionF quat; // quaternion defining rotation from local NED earth frame to body frame
516 Vector3F velocity; // velocity of body frame origin in local NED earth frame (m/sec)
517 Vector3F position; // position of body frame origin in local NED earth frame (m)
520 struct imu_elements {
521 Vector3F delAng; // IMU delta angle measurements in body frame (rad)
522 Vector3F delVel; // IMU delta velocity measurements in body frame (m/sec)
523 ftype delAngDT; // time interval over which delAng has been measured (sec)
524 ftype delVelDT; // time interval over which delVelDT has been measured (sec)
525 uint32_t time_ms; // measurement timestamp (msec)
526 uint8_t gyro_index;
527 uint8_t accel_index;
530 struct gps_elements : EKF_obs_element_t {
531 int32_t lat, lng; // latitude and longitude in 1e7 degrees
532 ftype hgt; // height of the GPS antenna in local NED earth frame (m)
533 Vector3F vel; // velocity of the GPS antenna in local NED earth frame (m/sec)
534 uint8_t sensor_idx; // unique integer identifying the GPS sensor
535 bool corrected; // true when the position and velocity have been corrected for sensor position
536 bool have_vz; // true when vertical velocity is valid
539 struct mag_elements : EKF_obs_element_t {
540 Vector3F mag; // body frame magnetic field measurements (Gauss)
543 struct baro_elements : EKF_obs_element_t {
544 ftype hgt; // height of the pressure sensor in local NED earth frame (m)
547 struct range_elements : EKF_obs_element_t {
548 ftype rng; // distance measured by the range sensor (m)
549 uint8_t sensor_idx; // integer either 0 or 1 uniquely identifying up to two range sensors
552 struct rng_bcn_elements : EKF_obs_element_t {
553 ftype rng; // range measurement to each beacon (m)
554 Vector3F beacon_posNED; // NED position of the beacon (m)
555 ftype rngErr; // range measurement error 1-std (m)
556 uint8_t beacon_ID; // beacon identification number
559 struct tas_elements : EKF_obs_element_t {
560 ftype tas; // true airspeed measurement (m/sec)
561 ftype tasVariance; // variance of true airspeed measurement (m/sec)^2
562 bool allowFusion; // true if measurement can be allowed to modify EKF states.
565 struct of_elements : EKF_obs_element_t {
566 Vector2F flowRadXY; // raw (non motion compensated) optical flow angular rates about the XY body axes (rad/sec)
567 Vector2F flowRadXYcomp; // motion compensated XY optical flow angular rates about the XY body axes (rad/sec)
568 Vector3F bodyRadXYZ; // body frame XYZ axis angular rates averaged across the optical flow measurement interval (rad/sec)
569 Vector3F body_offset; // XYZ position of the optical flow sensor in body frame (m)
572 struct vel_odm_elements : EKF_obs_element_t {
573 Vector3F vel; // XYZ velocity measured in body frame (m/s)
574 ftype velErr; // velocity measurement error 1-std (m/s)
575 Vector3F body_offset;// XYZ position of the velocity sensor in body frame (m)
576 Vector3F angRate; // angular rate estimated from odometry (rad/sec)
579 struct wheel_odm_elements : EKF_obs_element_t {
580 ftype delAng; // wheel rotation angle measured in body frame - positive is forward movement of vehicle (rad/s)
581 ftype radius; // wheel radius (m)
582 Vector3F hub_offset; // XYZ position of the wheel hub in body frame (m)
583 ftype delTime; // time interval that the measurement was accumulated over (sec)
586 // Specifies the rotation order used for the Tait-Bryan or Euler angles where alternative rotation orders are available
587 enum class rotationOrder {
588 TAIT_BRYAN_321=0,
589 TAIT_BRYAN_312=1
592 struct yaw_elements : EKF_obs_element_t {
593 ftype yawAng; // yaw angle measurement (rad)
594 ftype yawAngErr; // yaw angle 1SD measurement accuracy (rad)
595 rotationOrder order; // type specifiying Euler rotation order used, 0 = 321 (ZYX), 1 = 312 (ZXY)
598 struct ext_nav_elements : EKF_obs_element_t {
599 Vector3F pos; // XYZ position measured in a RH navigation frame (m)
600 ftype posErr; // spherical position measurement error 1-std (m)
601 bool posReset; // true when the position measurement has been reset
602 bool corrected; // true when the position has been corrected for sensor position
605 struct ext_nav_vel_elements : EKF_obs_element_t {
606 Vector3F vel; // velocity in NED (m/s)
607 ftype err; // velocity measurement error (m/s)
608 bool corrected; // true when the velocity has been corrected for sensor position
611 struct drag_elements : EKF_obs_element_t {
612 Vector2f accelXY; // measured specific force along the X and Y body axes (m/sec**2)
615 // bias estimates for the IMUs that are enabled but not being used
616 // by this core.
617 struct {
618 Vector3F gyro_bias;
619 Vector3F accel_bias;
620 } inactiveBias[INS_MAX_INSTANCES];
622 // Specify source of data to be used for a partial state reset
623 // Checking the availability and quality of the data source specified is the responsibility of the caller
624 enum class resetDataSource {
625 DEFAULT=0, // Use data source selected by reset function internal rules
626 GPS=1, // Use GPS
627 RNGBCN=2, // Use beacon range data
628 FLOW=3, // Use optical flow rates
629 BARO=4, // Use Baro height
630 MAG=5, // Use magnetometer data
631 RNGFND=6, // Use rangefinder data
632 EXTNAV=7 // Use external nav data
635 // specifies the method to be used when fusing yaw observations
636 enum class yawFusionMethod {
637 MAGNETOMETER=0,
638 GPS=1,
639 GSF=2,
640 STATIC=3,
641 PREDICTED=4,
642 EXTNAV=5,
645 // update the navigation filter status
646 void updateFilterStatus(void);
648 // update the quaternion, velocity and position states using IMU measurements
649 void UpdateStrapdownEquationsNED();
651 // calculate the predicted state covariance matrix
652 // Argument rotVarVecPtr is pointer to a vector defining the earth frame uncertainty variance of the quaternion states
653 // used to perform a reset of the quaternion state covariances only. Set to null for normal operation.
654 void CovariancePrediction(Vector3F *rotVarVecPtr);
656 // force symmetry on the state covariance matrix
657 void ForceSymmetry();
659 // constrain variances (diagonal terms) in the state covariance matrix
660 void ConstrainVariances();
662 // constrain states
663 void ConstrainStates();
665 // constrain earth field using WMM tables
666 void MagTableConstrain(void);
668 // fuse selected position, velocity and height measurements
669 void FuseVelPosNED();
671 // fuse body frame velocity measurements
672 void FuseBodyVel();
674 // fuse range beacon measurements
675 void FuseRngBcn();
677 // use range beacon measurements to calculate a static position
678 void FuseRngBcnStatic();
680 // calculate the offset from EKF vertical position datum to the range beacon system datum
681 void CalcRangeBeaconPosDownOffset(ftype obsVar, Vector3F &vehiclePosNED, bool aligning);
683 // fuse magnetometer measurements
684 void FuseMagnetometer();
686 // fuse true airspeed measurements
687 void FuseAirspeed();
689 // fuse synthetic sideslip measurement of zero
690 void FuseSideslip();
692 // zero specified range of rows in the state covariance matrix
693 void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last);
695 // zero specified range of columns in the state covariance matrix
696 void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last);
698 // Reset the stored output history to current data
699 void StoreOutputReset(void);
701 // Reset the stored output quaternion history to current EKF state
702 void StoreQuatReset(void);
704 // Rotate the stored output quaternion history through a quaternion rotation
705 void StoreQuatRotate(const QuaternionF &deltaQuat);
707 // calculate the NED earth spin vector in rad/sec
708 void calcEarthRateNED(Vector3F &omega, int32_t latitude) const;
710 // initialise the covariance matrix
711 void CovarianceInit();
713 // helper functions for readIMUData
714 bool readDeltaVelocity(uint8_t ins_index, Vector3F &dVel, ftype &dVel_dt);
715 bool readDeltaAngle(uint8_t ins_index, Vector3F &dAng, ftype &dAng_dt);
717 // helper functions for correcting IMU data
718 void correctDeltaAngle(Vector3F &delAng, ftype delAngDT, uint8_t gyro_index);
719 void correctDeltaVelocity(Vector3F &delVel, ftype delVelDT, uint8_t accel_index);
721 // update IMU delta angle and delta velocity measurements
722 void readIMUData();
724 // update estimate of inactive bias states
725 void learnInactiveBiases();
727 // check for new valid GPS data and update stored measurement if available
728 void readGpsData();
730 // check for new valid GPS yaw data
731 void readGpsYawData();
733 // check for new altitude measurement data and update stored measurement if available
734 void readBaroData();
736 // check for new magnetometer data and update store measurements if available
737 void readMagData();
739 // try changing compasses on compass failure or timeout
740 void tryChangeCompass(void);
742 // check for new airspeed data and update stored measurements if available
743 void readAirSpdData();
745 // check for new range beacon data and update stored measurements if available
746 void readRngBcnData();
748 // determine when to perform fusion of GPS position and velocity measurements
749 void SelectVelPosFusion();
751 // determine when to perform fusion of range measurements take relative to a beacon at a known NED position
752 void SelectRngBcnFusion();
754 // determine when to perform fusion of magnetometer measurements
755 void SelectMagFusion();
757 // determine when to perform fusion of true airspeed measurements
758 void SelectTasFusion();
760 // determine when to perform fusion of drag or synthetic sideslip measurements
761 void SelectBetaDragFusion();
763 // force alignment of the yaw angle using GPS velocity data
764 void realignYawGPS();
766 // initialise the earth magnetic field states using declination and current attitude and magnetometer measurements
768 // align the yaw angle for the quaternion states to the given yaw angle which should be at the fusion horizon
769 void alignYawAngle(const yaw_elements &yawAngData);
771 // update mag field states and associated variances using magnetomer and declination data
772 void resetMagFieldStates();
774 // reset yaw based on magnetic field sample
775 void setYawFromMag();
777 // zero stored variables
778 void InitialiseVariables();
780 // zero stored variables related to mag
781 void InitialiseVariablesMag();
783 // reset the horizontal position states uing the last GPS measurement
784 void ResetPosition(resetDataSource posResetSource);
786 // reset the stateStruct's NE position to the specified position
787 void ResetPositionNE(ftype posN, ftype posE);
789 // reset the stateStruct's D position
790 void ResetPositionD(ftype posD);
792 // reset velocity states using the last GPS measurement
793 void ResetVelocity(resetDataSource velResetSource);
795 // reset the vertical position state using the last height measurement
796 void ResetHeight(void);
798 // return true if we should use the airspeed sensor
799 bool useAirspeed(void) const;
801 // return true if the vehicle code has requested the filter to be ready for flight
802 bool readyToUseGPS(void) const;
804 // return true if the filter to be ready to use the beacon range measurements
805 bool readyToUseRangeBeacon(void) const;
807 // Check for filter divergence
808 void checkDivergence(void);
810 // Calculate weighting that is applied to IMU1 accel data to blend data from IMU's 1 and 2
811 void calcIMU_Weighting(ftype K1, ftype K2);
813 // return true if the filter is ready to start using optical flow measurements for position and velocity estimation
814 bool readyToUseOptFlow(void) const;
816 // return true if the filter is ready to start using body frame odometry measurements
817 bool readyToUseBodyOdm(void) const;
819 // return true if the filter to be ready to use external nav data
820 bool readyToUseExtNav(void) const;
822 // return true if we should use the range finder sensor
823 bool useRngFinder(void) const;
825 // determine when to perform fusion of optical flow measurements
826 void SelectFlowFusion();
828 // determine when to perform fusion of body frame odometry measurements
829 void SelectBodyOdomFusion();
831 // Estimate terrain offset using a single state EKF
832 void EstimateTerrainOffset(const of_elements &ofDataDelayed);
834 // fuse optical flow measurements into the main filter
835 // really_fuse should be true to actually fuse into the main filter, false to only calculate variances
836 void FuseOptFlow(const of_elements &ofDataDelayed, bool really_fuse);
838 // Control filter mode changes
839 void controlFilterModes();
841 // Determine if we are flying or on the ground
842 void detectFlight();
844 // Set inertial navigation aiding mode
845 void setAidingMode();
847 // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
848 // avoid unnecessary operations
849 void setWindMagStateLearningMode();
851 // Check the alignmnent status of the tilt attitude
852 // Used during initial bootstrap alignment of the filter
853 void checkAttitudeAlignmentStatus();
855 // Control reset of yaw and magnetic field states
856 void controlMagYawReset();
858 // set the latitude and longitude and height used to set the NED origin
859 // All NED positions calculated by the filter will be relative to this location
860 // returns false if the origin has already been set
861 bool setOrigin(const Location &loc);
863 // Assess GPS data quality and set gpsGoodToAlign
864 void calcGpsGoodToAlign(void);
866 // set the class variable true if the delta angle bias variances are sufficiently small
867 void checkGyroCalStatus(void);
869 // update inflight calculaton that determines if GPS data is good enough for reliable navigation
870 void calcGpsGoodForFlight(void);
872 // Read the range finder and take new measurements if available
873 // Apply a median filter to range finder data
874 void readRangeFinder();
876 // check if the vehicle has taken off during optical flow navigation by looking at inertial and range finder data
877 void detectOptFlowTakeoff(void);
879 // align the NE earth magnetic field states with the published declination
880 void alignMagStateDeclination();
882 // Fuse compass measurements using a direct yaw angle observation (doesn't require magnetic field states)
883 // Returns true if the fusion was successful
884 bool fuseEulerYaw(yawFusionMethod method);
886 // return the best Tait-Bryan rotation order to use
887 void bestRotationOrder(rotationOrder &order);
889 // Fuse declination angle to keep earth field declination from changing when we don't have earth relative observations.
890 // Input is 1-sigma uncertainty in published declination
891 void FuseDeclination(ftype declErr);
893 // return magnetic declination in radians
894 ftype MagDeclination(void) const;
896 // Propagate PVA solution forward from the fusion time horizon to the current time horizon
897 // using a simple observer
898 void calcOutputStates();
900 // calculate a filtered offset between baro height measurement and EKF height estimate
901 void calcFiltBaroOffset();
903 // correct the height of the EKF origin to be consistent with GPS Data using a Bayes filter.
904 void correctEkfOriginHeight();
906 // Select height data to be fused from the available baro, range finder and GPS sources
907 void selectHeightForFusion();
909 // zero attitude state covariances, but preserve variances
910 void zeroAttCovOnly();
912 // record a yaw reset event
913 void recordYawReset();
915 // record a magnetic field state reset event
916 void recordMagReset();
918 // effective value of MAG_CAL
919 MagCal effective_magCal(void) const;
921 // calculate the tilt error variance
922 void calcTiltErrorVariance(void);
924 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
925 // calculate the tilt error variance using an alternative numerical difference technique
926 // and log with value generated by NavEKF3_core::calcTiltErrorVariance()
927 void verifyTiltErrorVariance();
928 #endif
930 // update timing statistics structure
931 void updateTimingStatistics(void);
933 // Update the state index limit based on which states are active
934 void updateStateIndexLim(void);
936 // correct GPS data for antenna position
937 void CorrectGPSForAntennaOffset(gps_elements &gps_data) const;
939 // correct external navigation earth-frame position using sensor body-frame offset
940 void CorrectExtNavForSensorOffset(ext_nav_elements &ext_nav_data);
942 // correct external navigation earth-frame velocity using sensor body-frame offset
943 void CorrectExtNavVelForSensorOffset(ext_nav_vel_elements &ext_nav_vel_data) const;
945 // calculate velocity variances and innovations
946 // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration
947 // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration
948 // variances argument is updated with variances for each axis
949 void CalculateVelInnovationsAndVariances(const Vector3F &velocity, ftype noise, ftype accel_scale, Vector3F &innovations, Vector3F &variances) const;
951 // Runs the IMU prediction step for an independent GSF yaw estimator algorithm
952 // that uses IMU, GPS horizontal velocity and optionally true airspeed data.
953 void runYawEstimatorPrediction(void);
955 // Run the GPS velocity correction step for the GSF yaw estimator and use the
956 // yaw estimate to reset the main EKF yaw if requested
957 void runYawEstimatorCorrection(void);
959 // reset the quaternion states using the supplied yaw angle, maintaining the previous roll and pitch
960 // also reset the body to nav frame rotation matrix
961 // reset the quaternion state covariances using the supplied yaw variance
962 // yaw : new yaw angle (rad)
963 // yaw_variance : variance of new yaw angle (rad^2)
964 // order : enum defining Tait-Bryan rotation order used in calculation of the yaw angle
965 void resetQuatStateYawOnly(ftype yaw, ftype yawVariance, rotationOrder order);
967 // attempt to reset the yaw to the EKF-GSF value
968 // emergency_reset should be true if this reset is triggered by the loss of the yaw estimate
969 // returns false if unsuccessful
970 bool EKFGSF_resetMainFilterYaw(bool emergency_reset);
972 // returns true on success and populates yaw (in radians) and yawVariance (rad^2)
973 bool EKFGSF_getYaw(ftype &yaw, ftype &yawVariance) const;
975 // Fusion of body frame X and Y axis drag specific forces for multi-rotor wind estimation
976 void FuseDragForces();
977 void SelectDragFusion();
978 void SampleDragData(const imu_elements &imu);
980 bool getGPSLLH(struct Location &loc) const;
982 // Variables
983 bool statesInitialised; // boolean true when filter states have been initialised
984 bool magHealth; // boolean true if magnetometer has passed innovation consistency check
985 bool velTimeout; // boolean true if velocity measurements have failed innovation consistency check and timed out
986 bool posTimeout; // boolean true if position measurements have failed innovation consistency check and timed out
987 bool hgtTimeout; // boolean true if height measurements have failed innovation consistency check and timed out
988 bool magTimeout; // boolean true if magnetometer measurements have failed for too long and have timed out
989 bool tasTimeout; // boolean true if true airspeed measurements have failed for too long and have timed out
990 bool dragTimeout; // boolean true if drag measurements have failed for too long and have timed out
991 bool badIMUdata; // boolean true if the bad IMU data is detected
992 uint32_t badIMUdata_ms; // time stamp bad IMU data was last detected
993 uint32_t goodIMUdata_ms; // time stamp good IMU data was last detected
994 uint32_t vertVelVarClipCounter; // counter used to control reset of vertical velocity variance following collapse against the lower limit
996 ftype gpsNoiseScaler; // Used to scale the GPS measurement noise and consistency gates to compensate for operation with small satellite counts
997 Matrix24 P; // covariance matrix
998 EKF_IMU_buffer_t<imu_elements> storedIMU; // IMU data buffer
999 EKF_obs_buffer_t<gps_elements> storedGPS; // GPS data buffer
1000 EKF_obs_buffer_t<mag_elements> storedMag; // Magnetometer data buffer
1001 EKF_obs_buffer_t<baro_elements> storedBaro; // Baro data buffer
1002 EKF_obs_buffer_t<tas_elements> storedTAS; // TAS data buffer
1003 EKF_obs_buffer_t<range_elements> storedRange; // Range finder data buffer
1004 EKF_IMU_buffer_t<output_elements> storedOutput;// output state buffer
1005 Matrix3F prevTnb; // previous nav to body transformation used for INS earth rotation compensation
1006 ftype accNavMag; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2)
1007 ftype accNavMagHoriz; // magnitude of navigation accel in horizontal plane (m/s^2)
1008 Vector3F earthRateNED; // earths angular rate vector in NED (rad/s)
1009 ftype dtIMUavg; // expected time between IMU measurements (sec)
1010 ftype dtEkfAvg; // expected time between EKF updates (sec)
1011 ftype dt; // time lapsed since the last covariance prediction (sec)
1012 ftype hgtRate; // state for rate of change of height filter
1013 bool onGround; // true when the flight vehicle is definitely on the ground
1014 bool prevOnGround; // value of onGround from previous frame - used to detect transition
1015 bool inFlight; // true when the vehicle is definitely flying
1016 bool prevInFlight; // value inFlight from previous frame - used to detect transition
1017 bool manoeuvring; // boolean true when the flight vehicle is performing horizontal changes in velocity
1018 Vector6 innovVelPos; // innovation output for a group of measurements
1019 Vector6 varInnovVelPos; // innovation variance output for a group of measurements
1020 Vector6 velPosObs; // observations for combined velocity and positon group of measurements (3x1 m , 3x1 m/s)
1021 bool fuseVelData; // this boolean causes the velNED measurements to be fused
1022 bool fusePosData; // this boolean causes the posNE measurements to be fused
1023 bool fuseHgtData; // this boolean causes the hgtMea measurements to be fused
1024 Vector3F innovMag; // innovation output from fusion of X,Y,Z compass measurements
1025 Vector3F varInnovMag; // innovation variance output from fusion of X,Y,Z compass measurements
1026 ftype innovVtas; // innovation output from fusion of airspeed measurements
1027 ftype varInnovVtas; // innovation variance output from fusion of airspeed measurements
1028 ftype defaultAirSpeed; // default equivalent airspeed in m/s to be used if the measurement is unavailable. Do not use if not positive.
1029 ftype defaultAirSpeedVariance; // default equivalent airspeed variance in (m/s)**2 to be used when defaultAirSpeed is specified.
1030 bool magFusePerformed; // boolean set to true when magnetometer fusion has been perfomred in that time step
1031 MagCal effectiveMagCal; // the actual mag calibration being used as the default
1032 uint32_t prevTasStep_ms; // time stamp of last TAS fusion step
1033 uint32_t prevBetaDragStep_ms; // time stamp of last synthetic sideslip fusion step
1034 ftype innovBeta; // synthetic sideslip innovation (rad)
1035 uint32_t lastMagUpdate_us; // last time compass was updated in usec
1036 uint32_t lastMagRead_ms; // last time compass data was successfully read
1037 Vector3F velDotNED; // rate of change of velocity in NED frame
1038 Vector3F velDotNEDfilt; // low pass filtered velDotNED
1039 uint32_t imuSampleTime_ms; // time that the last IMU value was taken
1040 bool tasDataToFuse; // true when new airspeed data is waiting to be fused
1041 uint32_t lastBaroReceived_ms; // time last time we received baro height data
1042 uint16_t hgtRetryTime_ms; // time allowed without use of height measurements before a height timeout is declared
1043 uint32_t lastVelPassTime_ms; // time stamp when GPS velocity measurement last passed innovation consistency check (msec)
1044 uint32_t lastPosPassTime_ms; // time stamp when GPS position measurement last passed innovation consistency check (msec)
1045 uint32_t lastHgtPassTime_ms; // time stamp when height measurement last passed innovation consistency check (msec)
1046 uint32_t lastTasPassTime_ms; // time stamp when airspeed measurement last passed innovation consistency check (msec)
1047 uint32_t lastTasFailTime_ms; // time stamp when airspeed measurement last failed innovation consistency check (msec)
1048 uint32_t lastTimeGpsReceived_ms;// last time we received GPS data
1049 uint32_t timeAtLastAuxEKF_ms; // last time the auxiliary filter was run to fuse range or optical flow measurements
1050 uint32_t lastHealthyMagTime_ms; // time the magnetometer was last declared healthy
1051 bool allMagSensorsFailed; // true if all magnetometer sensors have timed out on this flight and we are no longer using magnetometer data
1052 uint32_t lastSynthYawTime_ms; // time stamp when yaw observation was last fused (msec)
1053 uint32_t ekfStartTime_ms; // time the EKF was started (msec)
1054 Vector2F lastKnownPositionNE; // last known position
1055 float lastKnownPositionD; // last known height
1056 uint32_t lastLaunchAccelTime_ms;
1057 ftype velTestRatio; // sum of squares of GPS velocity innovation divided by fail threshold
1058 ftype posTestRatio; // sum of squares of GPS position innovation divided by fail threshold
1059 ftype hgtTestRatio; // sum of squares of baro height innovation divided by fail threshold
1060 Vector3F magTestRatio; // sum of squares of magnetometer innovations divided by fail threshold
1061 ftype tasTestRatio; // sum of squares of true airspeed innovation divided by fail threshold
1062 bool inhibitWindStates; // true when wind states and covariances are to remain constant
1063 bool windStatesAligned; // true when wind states have been aligned
1064 bool inhibitMagStates; // true when magnetic field states are inactive
1065 bool lastInhibitMagStates; // previous inhibitMagStates
1066 bool needMagBodyVarReset; // we need to reset mag body variances at next CovariancePrediction
1067 bool needEarthBodyVarReset; // we need to reset mag earth variances at next CovariancePrediction
1068 bool inhibitDelAngBiasStates; // true when IMU delta angle bias states are inactive
1069 bool gpsIsInUse; // bool true when GPS data is being used to correct states estimates
1070 struct Location EKF_origin; // LLH origin of the NED axis system, internal only
1071 struct Location &public_origin; // LLH origin of the NED axis system, public functions
1072 bool validOrigin; // true when the EKF origin is valid
1073 ftype gpsSpdAccuracy; // estimated speed accuracy in m/s returned by the GPS receiver
1074 ftype gpsPosAccuracy; // estimated position accuracy in m returned by the GPS receiver
1075 ftype gpsHgtAccuracy; // estimated height accuracy in m returned by the GPS receiver
1076 uint32_t lastGpsVelFail_ms; // time of last GPS vertical velocity consistency check fail
1077 uint32_t lastGpsVelPass_ms; // time of last GPS vertical velocity consistency check pass
1078 uint32_t lastGpsAidBadTime_ms; // time in msec gps aiding was last detected to be bad
1079 ftype posDownAtTakeoff; // flight vehicle vertical position sampled at transition from on-ground to in-air and used as a reference (m)
1080 bool useGpsVertVel; // true if GPS vertical velocity should be used
1081 ftype yawResetAngle; // Change in yaw angle due to last in-flight yaw reset in radians. A positive value means the yaw angle has increased.
1082 uint32_t lastYawReset_ms; // System time at which the last yaw reset occurred. Returned by getLastYawResetAngle
1083 bool tiltAlignComplete; // true when tilt alignment is complete
1084 bool yawAlignComplete; // true when yaw alignment is complete
1085 bool magStateInitComplete; // true when the magnetic field states have been initialised
1086 uint8_t stateIndexLim; // Max state index used during matrix and array operations
1087 imu_elements imuDataDelayed; // IMU data at the fusion time horizon
1088 imu_elements imuDataNew; // IMU data at the current time horizon
1089 imu_elements imuDataDownSampledNew; // IMU data at the current time horizon that has been downsampled to a 100Hz rate
1090 QuaternionF imuQuatDownSampleNew; // Quaternion obtained by rotating through the IMU delta angles since the start of the current down sampled frame
1091 baro_elements baroDataNew; // Baro data at the current time horizon
1092 baro_elements baroDataDelayed; // Baro data at the fusion time horizon
1093 range_elements rangeDataNew; // Range finder data at the current time horizon
1094 range_elements rangeDataDelayed;// Range finder data at the fusion time horizon
1095 tas_elements tasDataNew; // TAS data at the current time horizon
1096 tas_elements tasDataDelayed; // TAS data at the fusion time horizon
1097 bool usingDefaultAirspeed; // true when a default airspeed is being used instead of a measured value
1098 mag_elements magDataDelayed; // Magnetometer data at the fusion time horizon
1099 gps_elements gpsDataNew; // GPS data at the current time horizon
1100 gps_elements gpsDataDelayed; // GPS data at the fusion time horizon
1101 uint8_t last_gps_idx; // sensor ID of the GPS receiver used for the last fusion or reset
1102 output_elements outputDataNew; // output state data at the current time step
1103 output_elements outputDataDelayed; // output state data at the current time step
1104 Vector3F delAngCorrection; // correction applied to delta angles used by output observer to track the EKF
1105 Vector3F velErrintegral; // integral of output predictor NED velocity tracking error (m)
1106 Vector3F posErrintegral; // integral of output predictor NED position tracking error (m.sec)
1107 ftype badImuVelErrIntegral; // integral of output predictor D velocity tracking error when bad IMU data is detected (m)
1108 ftype innovYaw; // compass yaw angle innovation (rad)
1109 uint32_t timeTasReceived_ms; // time last TAS data was received (msec)
1110 bool gpsGoodToAlign; // true when the GPS quality can be used to initialise the navigation system
1111 uint32_t magYawResetTimer_ms; // timer in msec used to track how long good magnetometer data is failing innovation consistency checks
1112 bool consistentMagData; // true when the magnetometers are passing consistency checks
1113 bool motorsArmed; // true when the motors have been armed
1114 bool prevMotorsArmed; // value of motorsArmed from previous frame
1115 bool posVelFusionDelayed; // true when the position and velocity fusion has been delayed
1116 bool optFlowFusionDelayed; // true when the optical flow fusion has been delayed
1117 bool airSpdFusionDelayed; // true when the air speed fusion has been delayed
1118 bool sideSlipFusionDelayed; // true when the sideslip fusion has been delayed
1119 bool airDataFusionWindOnly; // true when sideslip and airspeed fusion is only allowed to modify the wind states
1120 Vector3F lastMagOffsets; // Last magnetometer offsets from COMPASS_ parameters. Used to detect parameter changes.
1121 bool lastMagOffsetsValid; // True when lastMagOffsets has been initialized
1122 Vector2F posResetNE; // Change in North/East position due to last in-flight reset in metres. Returned by getLastPosNorthEastReset
1123 uint32_t lastPosReset_ms; // System time at which the last position reset occurred. Returned by getLastPosNorthEastReset
1124 Vector2F velResetNE; // Change in North/East velocity due to last in-flight reset in metres/sec. Returned by getLastVelNorthEastReset
1125 uint32_t lastVelReset_ms; // System time at which the last velocity reset occurred. Returned by getLastVelNorthEastReset
1126 ftype posResetD; // Change in Down position due to last in-flight reset in metres. Returned by getLastPosDowntReset
1127 uint32_t lastPosResetD_ms; // System time at which the last position reset occurred. Returned by getLastPosDownReset
1128 ftype yawTestRatio; // square of magnetometer yaw angle innovation divided by fail threshold
1129 QuaternionF prevQuatMagReset; // Quaternion from the last time the magnetic field state reset condition test was performed
1130 ftype hgtInnovFiltState; // state used for fitering of the height innovations used for pre-flight checks
1131 uint8_t magSelectIndex; // Index of the magnetometer that is being used by the EKF
1132 bool runUpdates; // boolean true when the EKF updates can be run
1133 uint32_t framesSincePredict; // number of frames lapsed since EKF instance did a state prediction
1134 bool startPredictEnabled; // boolean true when the frontend has given permission to start a new state prediciton cycle
1135 uint8_t localFilterTimeStep_ms; // average number of msec between filter updates
1136 ftype posDownObsNoise; // observation noise variance on the vertical position used by the state and covariance update step (m^2)
1137 Vector3F delAngCorrected; // corrected IMU delta angle vector at the EKF time horizon (rad)
1138 Vector3F delVelCorrected; // corrected IMU delta velocity vector at the EKF time horizon (m/s)
1139 bool magFieldLearned; // true when the magnetic field has been learned
1140 uint32_t wasLearningCompass_ms; // time when we were last waiting for compass learn to complete
1141 Vector3F earthMagFieldVar; // NED earth mag field variances for last learned field (mGauss^2)
1142 Vector3F bodyMagFieldVar; // XYZ body mag field variances for last learned field (mGauss^2)
1143 bool delAngBiasLearned; // true when the gyro bias has been learned
1144 nav_filter_status filterStatus; // contains the status of various filter outputs
1145 ftype ekfOriginHgtVar; // Variance of the EKF WGS-84 origin height estimate (m^2)
1146 double ekfGpsRefHgt; // floating point representation of the WGS-84 reference height used to convert GPS height to local height (m)
1147 uint32_t lastOriginHgtTime_ms; // last time the ekf's WGS-84 origin height was corrected
1148 Vector3F outputTrackError; // attitude (rad), velocity (m/s) and position (m) tracking error magnitudes from the output observer
1149 Vector3F velOffsetNED; // This adds to the earth frame velocity estimate at the IMU to give the velocity at the body origin (m/s)
1150 Vector3F posOffsetNED; // This adds to the earth frame position estimate at the IMU to give the position at the body origin (m)
1151 uint32_t firstInitTime_ms; // First time the initialise function was called (msec)
1152 uint32_t lastInitFailReport_ms; // Last time the buffer initialisation failure report was sent (msec)
1153 ftype tiltErrorVariance; // variance of the angular uncertainty measured perpendicular to the vertical (rad^2)
1155 // variables used to calculate a vertical velocity that is kinematically consistent with the vertical position
1156 struct {
1157 ftype pos;
1158 ftype vel;
1159 ftype acc;
1160 } vertCompFiltState;
1162 // variables used by the pre-initialisation GPS checks
1163 struct Location gpsloc_prev; // LLH location of previous GPS measurement
1164 uint32_t lastPreAlignGpsCheckTime_ms; // last time in msec the GPS quality was checked during pre alignment checks
1165 ftype gpsDriftNE; // amount of drift detected in the GPS position during pre-flight GPs checks
1166 ftype gpsVertVelFilt; // amount of filtered vertical GPS velocity detected during pre-flight GPS checks
1167 ftype gpsHorizVelFilt; // amount of filtered horizontal GPS velocity detected during pre-flight GPS checks
1169 // variable used by the in-flight GPS quality check
1170 bool gpsSpdAccPass; // true when reported GPS speed accuracy passes in-flight checks
1171 bool gpsVertAccPass; // true when reported GPS vertical accuracy passes in-flight checks
1172 bool ekfInnovationsPass; // true when GPS innovations pass in-flight checks
1173 ftype sAccFilterState1; // state variable for LPF applied to reported GPS speed accuracy
1174 ftype sAccFilterState2; // state variable for peak hold filter applied to reported GPS speed
1175 uint32_t lastGpsCheckTime_ms; // last time in msec the GPS quality was checked
1176 uint32_t lastGpsInnovPassTime_ms; // last time in msec the GPS innovations passed
1177 uint32_t lastGpsInnovFailTime_ms; // last time in msec the GPS innovations failed
1178 uint32_t lastGpsVertAccPassTime_ms; // last time in msec the GPS vertical accuracy test passed
1179 uint32_t lastGpsVertAccFailTime_ms; // last time in msec the GPS vertical accuracy test failed
1180 bool gpsAccuracyGood; // true when the GPS accuracy is considered to be good enough for safe flight.
1181 bool gpsAccuracyGoodForAltitude; // true when the GPS accuracy is considered to be good enough to use it as an altitude source.
1182 Vector3F gpsVelInnov; // gps velocity innovations
1183 Vector3F gpsVelVarInnov; // gps velocity innovation variances
1184 uint32_t gpsVelInnovTime_ms; // system time that gps velocity innovations were recorded (to detect timeouts)
1186 // variables added for optical flow fusion
1187 EKF_obs_buffer_t<of_elements> storedOF; // OF data buffer
1188 bool flowDataValid; // true while optical flow data is still fresh
1189 Vector2F auxFlowObsInnov; // optical flow rate innovation from 1-state terrain offset estimator
1190 uint32_t flowValidMeaTime_ms; // time stamp from latest valid flow measurement (msec)
1191 uint32_t rngValidMeaTime_ms; // time stamp from latest valid range measurement (msec)
1192 uint32_t flowMeaTime_ms; // time stamp from latest flow measurement (msec)
1193 uint32_t gndHgtValidTime_ms; // time stamp from last terrain offset state update (msec)
1194 Vector2 flowVarInnov; // optical flow innovations variances (rad/sec)^2
1195 Vector2 flowInnov; // optical flow LOS innovations (rad/sec)
1196 uint32_t flowInnovTime_ms; // system time that optical flow innovations and variances were recorded (to detect timeouts)
1197 ftype Popt; // Optical flow terrain height state covariance (m^2)
1198 ftype terrainState; // terrain position state (m)
1199 ftype prevPosN; // north position at last measurement
1200 ftype prevPosE; // east position at last measurement
1201 ftype varInnovRng; // range finder observation innovation variance (m^2)
1202 ftype innovRng; // range finder observation innovation (m)
1203 struct {
1204 uint32_t timestamp_ms; // system timestamp of last correct optical flow sample (used for calibration)
1205 Vector2f flowRate; // latest corrected optical flow flow rate (used for calibration)
1206 Vector2f bodyRate; // latest corrected optical flow body rate (used for calibration)
1207 Vector2f losPred; // EKF estimated component of flowRate that comes from vehicle movement (not rotation)
1208 } flowCalSample;
1210 ftype hgtMea; // height measurement derived from either baro, gps or range finder data (m)
1211 bool inhibitGndState; // true when the terrain position state is to remain constant
1212 uint32_t prevFlowFuseTime_ms; // time both flow measurement components passed their innovation consistency checks
1213 Vector2 flowTestRatio; // square of optical flow innovations divided by fail threshold used by main filter where >1.0 is a fail
1214 Vector2F auxFlowTestRatio; // sum of squares of optical flow innovation divided by fail threshold used by 1-state terrain offset estimator
1215 ftype R_LOS; // variance of optical flow rate measurements (rad/sec)^2
1216 ftype auxRngTestRatio; // square of range finder innovations divided by fail threshold used by main filter where >1.0 is a fail
1217 Vector2F flowGyroBias; // bias error of optical flow sensor gyro output
1218 bool rangeDataToFuse; // true when valid range finder height data has arrived at the fusion time horizon.
1219 bool baroDataToFuse; // true when valid baro height finder data has arrived at the fusion time horizon.
1220 bool gpsDataToFuse; // true when valid GPS data has arrived at the fusion time horizon.
1221 bool magDataToFuse; // true when valid magnetometer data has arrived at the fusion time horizon
1222 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.
1223 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.
1224 AID_RELATIVE=2 // only optical flow aiding is being used so position estimates will be relative
1226 AidingMode PV_AidingMode; // Defines the preferred mode for aiding of velocity and position estimates from the INS
1227 AidingMode PV_AidingModePrev; // Value of PV_AidingMode from the previous frame - used to detect transitions
1228 bool gndOffsetValid; // true when the ground offset state can still be considered valid
1229 Vector3F delAngBodyOF; // bias corrected delta angle of the vehicle IMU measured summed across the time since the last OF measurement
1230 ftype delTimeOF; // time that delAngBodyOF is summed across
1231 bool flowFusionActive; // true when optical flow fusion is active
1233 Vector3F accelPosOffset; // position of IMU accelerometer unit in body frame (m)
1235 // Range finder
1236 ftype baroHgtOffset; // offset applied when when switching to use of Baro height
1237 ftype rngOnGnd; // Expected range finder reading in metres when vehicle is on ground
1238 ftype storedRngMeas[2][3]; // Ringbuffer of stored range measurements for dual range sensors
1239 uint32_t storedRngMeasTime_ms[2][3]; // Ringbuffers of stored range measurement times for dual range sensors
1240 uint32_t lastRngMeasTime_ms; // Timestamp of last range measurement
1241 uint8_t rngMeasIndex[2]; // Current range measurement ringbuffer index for dual range sensors
1242 bool terrainHgtStable; // true when the terrain height is stable enough to be used as a height reference
1244 // body frame odometry fusion
1245 #if EK3_FEATURE_BODY_ODOM
1246 EKF_obs_buffer_t<vel_odm_elements> storedBodyOdm; // body velocity data buffer
1247 vel_odm_elements bodyOdmDataNew; // Body frame odometry data at the current time horizon
1248 vel_odm_elements bodyOdmDataDelayed; // Body frame odometry data at the fusion time horizon
1249 #endif
1250 uint32_t lastbodyVelPassTime_ms; // time stamp when the body velocity measurement last passed innovation consistency checks (msec)
1251 Vector3 bodyVelTestRatio; // Innovation test ratios for body velocity XYZ measurements
1252 Vector3 varInnovBodyVel; // Body velocity XYZ innovation variances (m/sec)^2
1253 Vector3 innovBodyVel; // Body velocity XYZ innovations (m/sec)
1254 uint32_t prevBodyVelFuseTime_ms; // previous time all body velocity measurement components passed their innovation consistency checks (msec)
1255 uint32_t bodyOdmMeasTime_ms; // time body velocity measurements were accepted for input to the data buffer (msec)
1256 bool bodyVelFusionDelayed; // true when body frame velocity fusion has been delayed
1257 bool bodyVelFusionActive; // true when body frame velocity fusion is active
1259 #if EK3_FEATURE_BODY_ODOM
1260 // wheel sensor fusion
1261 EKF_obs_buffer_t<wheel_odm_elements> storedWheelOdm; // body velocity data buffer
1262 wheel_odm_elements wheelOdmDataDelayed; // Body frame odometry data at the fusion time horizon
1263 #endif
1265 // GPS yaw sensor fusion
1266 uint32_t yawMeasTime_ms; // system time GPS yaw angle was last input to the data buffer
1267 EKF_obs_buffer_t<yaw_elements> storedYawAng; // GPS yaw angle buffer
1268 yaw_elements yawAngDataNew; // GPS yaw angle at the current time horizon
1269 yaw_elements yawAngDataDelayed; // GPS yaw angle at the fusion time horizon
1270 yaw_elements yawAngDataStatic; // yaw angle (regardless of yaw source) when the vehicle was last on ground and not moving
1272 // Range Beacon Sensor Fusion
1273 EKF_obs_buffer_t<rng_bcn_elements> storedRangeBeacon; // Beacon range buffer
1274 rng_bcn_elements rngBcnDataDelayed; // Range beacon data at the fusion time horizon
1275 uint32_t lastRngBcnPassTime_ms; // time stamp when the range beacon measurement last passed innovation consistency checks (msec)
1276 ftype rngBcnTestRatio; // Innovation test ratio for range beacon measurements
1277 bool rngBcnHealth; // boolean true if range beacon measurements have passed innovation consistency check
1278 ftype varInnovRngBcn; // range beacon observation innovation variance (m^2)
1279 ftype innovRngBcn; // range beacon observation innovation (m)
1280 uint32_t lastTimeRngBcn_ms[4]; // last time we received a range beacon measurement (msec)
1281 bool rngBcnDataToFuse; // true when there is new range beacon data to fuse
1282 Vector3F beaconVehiclePosNED; // NED position estimate from the beacon system (NED)
1283 ftype beaconVehiclePosErr; // estimated position error from the beacon system (m)
1284 uint32_t rngBcnLast3DmeasTime_ms; // last time the beacon system returned a 3D fix (msec)
1285 bool rngBcnGoodToAlign; // true when the range beacon systems 3D fix can be used to align the filter
1286 uint8_t lastRngBcnChecked; // index of the last range beacon checked for data
1287 Vector3F receiverPos; // receiver NED position (m) - alignment 3 state filter
1288 ftype receiverPosCov[3][3]; // Receiver position covariance (m^2) - alignment 3 state filter (
1289 bool rngBcnAlignmentStarted; // True when the initial position alignment using range measurements has started
1290 bool rngBcnAlignmentCompleted; // True when the initial position alignment using range measurements has finished
1291 uint8_t lastBeaconIndex; // Range beacon index last read - used during initialisation of the 3-state filter
1292 Vector3F rngBcnPosSum; // Sum of range beacon NED position (m) - used during initialisation of the 3-state filter
1293 uint8_t numBcnMeas; // Number of beacon measurements - used during initialisation of the 3-state filter
1294 ftype rngSum; // Sum of range measurements (m) - used during initialisation of the 3-state filter
1295 uint8_t N_beacons; // Number of range beacons in use
1296 ftype maxBcnPosD; // maximum position of all beacons in the down direction (m)
1297 ftype minBcnPosD; // minimum position of all beacons in the down direction (m)
1298 bool usingMinHypothesis; // true when the min beacon constellation offset hypothesis is being used
1300 ftype bcnPosDownOffsetMax; // Vertical position offset of the beacon constellation origin relative to the EKF origin (m)
1301 ftype bcnPosOffsetMaxVar; // Variance of the bcnPosDownOffsetMax state (m)
1302 ftype maxOffsetStateChangeFilt; // Filtered magnitude of the change in bcnPosOffsetHigh
1304 ftype bcnPosDownOffsetMin; // Vertical position offset of the beacon constellation origin relative to the EKF origin (m)
1305 ftype bcnPosOffsetMinVar; // Variance of the bcnPosDownOffsetMin state (m)
1306 ftype minOffsetStateChangeFilt; // Filtered magnitude of the change in bcnPosOffsetLow
1308 Vector3F bcnPosOffsetNED; // NED position of the beacon origin in earth frame (m)
1309 bool bcnOriginEstInit; // True when the beacon origin has been initialised
1311 // Range Beacon Fusion Debug Reporting
1312 uint8_t rngBcnFuseDataReportIndex;// index of range beacon fusion data last reported
1313 struct rngBcnFusionReport_t {
1314 ftype rng; // measured range to beacon (m)
1315 ftype innov; // range innovation (m)
1316 ftype innovVar; // innovation variance (m^2)
1317 ftype testRatio; // innovation consistency test ratio
1318 Vector3F beaconPosNED; // beacon NED position
1319 } *rngBcnFusionReport;
1321 #if EK3_FEATURE_DRAG_FUSION
1322 // drag fusion for multicopter wind estimation
1323 EKF_obs_buffer_t<drag_elements> storedDrag;
1324 drag_elements dragSampleDelayed;
1325 drag_elements dragDownSampled; // down sampled from filter prediction rate to observation rate
1326 uint8_t dragSampleCount; // number of drag specific force samples accumulated at the filter prediction rate
1327 ftype dragSampleTimeDelta; // time integral across all samples used to form _drag_down_sampled (sec)
1328 Vector2F innovDrag; // multirotor drag measurement innovation (m/sec**2)
1329 Vector2F innovDragVar; // multirotor drag measurement innovation variance ((m/sec**2)**2)
1330 Vector2F dragTestRatio; // drag innovation consistency check ratio
1331 #endif
1332 uint32_t lastDragPassTime_ms; // system time that drag samples were last successfully fused
1333 bool dragFusionEnabled;
1335 // height source selection logic
1336 AP_NavEKF_Source::SourceZ activeHgtSource; // active height source
1337 AP_NavEKF_Source::SourceZ prevHgtSource; // previous height source used to detect changes in source
1339 // Movement detector
1340 bool takeOffDetected; // true when takeoff for optical flow navigation has been detected
1341 ftype rngAtStartOfFlight; // range finder measurement at start of flight
1342 uint32_t timeAtArming_ms; // time in msec that the vehicle armed
1344 // baro ground effect
1345 ftype meaHgtAtTakeOff; // height measured at commencement of takeoff
1347 // control of post takeoff magnetic field and heading resets
1348 bool finalInflightYawInit; // true when the final post takeoff initialisation of yaw angle has been performed
1349 uint8_t magYawAnomallyCount; // Number of times the yaw has been reset due to a magnetic anomaly during initial ascent
1350 bool finalInflightMagInit; // true when the final post takeoff initialisation of magnetic field states been performed
1351 bool magStateResetRequest; // true if magnetic field states need to be reset using the magnetomter measurements
1352 bool magYawResetRequest; // true if the vehicle yaw and magnetic field states need to be reset using the magnetometer measurements
1353 bool gpsYawResetRequest; // true if the vehicle yaw needs to be reset to the GPS course
1354 ftype posDownAtLastMagReset; // vertical position last time the mag states were reset (m)
1355 ftype yawInnovAtLastMagReset; // magnetic yaw innovation last time the yaw and mag field states were reset (rad)
1356 QuaternionF quatAtLastMagReset; // quaternion states last time the mag states were reset
1358 // Used by on ground movement check required when operating on ground without a yaw reference
1359 ftype gyro_diff; // filtered gyro difference (rad/s)
1360 ftype accel_diff; // filtered acceerometer difference (m/s/s)
1361 Vector3F gyro_prev; // gyro vector from previous time step (rad/s)
1362 Vector3F accel_prev; // accelerometer vector from previous time step (m/s/s)
1363 bool onGroundNotMoving; // true when on the ground and not moving
1364 uint32_t lastMoveCheckLogTime_ms; // last time the movement check data was logged (msec)
1366 // variables used to inhibit accel bias learning
1367 bool inhibitDelVelBiasStates; // true when all IMU delta velocity bias states are de-activated
1368 bool dvelBiasAxisInhibit[3] {}; // true when IMU delta velocity bias states for a specific axis is de-activated
1369 Vector3F dvelBiasAxisVarPrev; // saved delta velocity XYZ bias variances (m/sec)**2
1371 #if EK3_FEATURE_EXTERNAL_NAV
1372 // external navigation fusion
1373 EKF_obs_buffer_t<ext_nav_elements> storedExtNav; // external navigation data buffer
1374 ext_nav_elements extNavDataDelayed; // External nav at the fusion time horizon
1375 uint32_t extNavMeasTime_ms; // time external measurements were accepted for input to the data buffer (msec)
1376 uint32_t extNavLastPosResetTime_ms; // last time the external nav systen performed a position reset (msec)
1377 bool extNavDataToFuse; // true when there is new external nav data to fuse
1378 bool extNavUsedForPos; // true when the external nav data is being used as a position reference.
1379 EKF_obs_buffer_t<ext_nav_vel_elements> storedExtNavVel; // external navigation velocity data buffer
1380 ext_nav_vel_elements extNavVelDelayed; // external navigation velocity data at the fusion time horizon. Already corrected for sensor position
1381 uint32_t extNavVelMeasTime_ms; // time external navigation velocity measurements were accepted for input to the data buffer (msec)
1382 bool extNavVelToFuse; // true when there is new external navigation velocity to fuse
1383 Vector3F extNavVelInnov; // external nav velocity innovations
1384 Vector3F extNavVelVarInnov; // external nav velocity innovation variances
1385 uint32_t extNavVelInnovTime_ms; // system time that external nav velocity innovations were recorded (to detect timeouts)
1386 EKF_obs_buffer_t<yaw_elements> storedExtNavYawAng; // external navigation yaw angle buffer
1387 yaw_elements extNavYawAngDataDelayed; // external navigation yaw angle at the fusion time horizon
1388 uint32_t last_extnav_yaw_fusion_ms; // system time that external nav yaw was last fused
1389 #endif // EK3_FEATURE_EXTERNAL_NAV
1390 bool useExtNavVel; // true if external nav velocity should be used
1392 // flags indicating severe numerical errors in innovation variance calculation for different fusion operations
1393 struct {
1394 bool bad_xmag:1;
1395 bool bad_ymag:1;
1396 bool bad_zmag:1;
1397 bool bad_airspeed:1;
1398 bool bad_sideslip:1;
1399 bool bad_nvel:1;
1400 bool bad_evel:1;
1401 bool bad_dvel:1;
1402 bool bad_npos:1;
1403 bool bad_epos:1;
1404 bool bad_dpos:1;
1405 bool bad_yaw:1;
1406 bool bad_decl:1;
1407 bool bad_xflow:1;
1408 bool bad_yflow:1;
1409 bool bad_rngbcn:1;
1410 bool bad_xvel:1;
1411 bool bad_yvel:1;
1412 bool bad_zvel:1;
1413 } faultStatus;
1415 // flags indicating which GPS quality checks are failing
1416 union {
1417 struct {
1418 bool bad_sAcc:1;
1419 bool bad_hAcc:1;
1420 bool bad_vAcc:1;
1421 bool bad_yaw:1;
1422 bool bad_sats:1;
1423 bool bad_VZ:1;
1424 bool bad_horiz_drift:1;
1425 bool bad_hdop:1;
1426 bool bad_vert_vel:1;
1427 bool bad_fix:1;
1428 bool bad_horiz_vel:1;
1430 uint16_t value;
1431 } gpsCheckStatus;
1433 // states held by magnetometer fusion across time steps
1434 // magnetometer X,Y,Z measurements are fused across three time steps
1435 // to level computational load as this is an expensive operation
1436 struct {
1437 ftype q0;
1438 ftype q1;
1439 ftype q2;
1440 ftype q3;
1441 ftype magN;
1442 ftype magE;
1443 ftype magD;
1444 ftype magXbias;
1445 ftype magYbias;
1446 ftype magZbias;
1447 Matrix3F DCM;
1448 Vector3F MagPred;
1449 ftype R_MAG;
1450 Vector9 SH_MAG;
1451 } mag_state;
1453 // string representing last reason for prearm failure
1454 char prearm_fail_string[40];
1456 // earth field from WMM tables
1457 bool have_table_earth_field; // true when we have initialised table_earth_field_ga
1458 Vector3F table_earth_field_ga; // earth field from WMM tables
1459 ftype table_declination; // declination in radians from the tables
1461 // 1Hz update
1462 uint32_t last_oneHz_ms;
1463 void oneHzUpdate(void);
1465 // move EKF origin at 1Hz
1466 void moveEKFOrigin(void);
1468 // handle earth field updates
1469 void getEarthFieldTable(const Location &loc);
1470 void checkUpdateEarthField(void);
1472 // timing statistics
1473 struct ekf_timing timing;
1475 // when was attitude filter status last non-zero?
1476 uint32_t last_filter_ok_ms;
1478 // should we assume zero sideslip?
1479 bool assume_zero_sideslip(void) const;
1481 // vehicle specific initial gyro bias uncertainty
1482 ftype InitialGyroBiasUncertainty(void) const;
1485 learn magnetometer biases from GPS yaw. Return true if the
1486 resulting mag vector is close enough to the one predicted by GPS
1487 yaw to use it for fallback
1489 bool learnMagBiasFromGPS(void);
1491 uint32_t last_gps_yaw_ms; // last time the EKF attempted to use the GPS yaw
1492 uint32_t last_gps_yaw_fuse_ms; // last time the EKF successfully fused the GPS yaw
1493 bool gps_yaw_mag_fallback_ok;
1494 bool gps_yaw_mag_fallback_active;
1495 uint8_t gps_yaw_fallback_good_counter;
1498 Update the on ground and not moving check.
1499 Should be called once per IMU update.
1500 Only updates when on ground and when operating with an external yaw sensor
1502 void updateMovementCheck(void);
1504 // The following declarations are used to control when the main navigation filter resets it's yaw to the estimate provided by the GSF
1505 uint32_t EKFGSF_yaw_reset_ms; // timestamp of last emergency yaw reset (uSec)
1506 uint32_t EKFGSF_yaw_reset_request_ms; // timestamp of last emergency yaw reset request (uSec)
1507 uint8_t EKFGSF_yaw_reset_count; // number of emergency yaw resets performed
1508 bool EKFGSF_run_filterbank; // true when the filter bank is active
1509 uint8_t EKFGSF_yaw_valid_count; // number of updates since the last invalid yaw estimate
1511 // logging timestamps
1512 uint32_t lastLogTime_ms;
1513 uint32_t lastUpdateTime_ms;
1514 uint32_t lastEkfStateVarLogTime_ms;
1515 uint32_t lastTimingLogTime_ms;
1517 // bits in EK3_AFFINITY
1518 enum ekf_affinity {
1519 EKF_AFFINITY_GPS = (1U<<0),
1520 EKF_AFFINITY_BARO = (1U<<1),
1521 EKF_AFFINITY_MAG = (1U<<2),
1522 EKF_AFFINITY_ARSP = (1U<<3),
1525 // update selected_sensors for this core
1526 void update_sensor_selection(void);
1527 void update_gps_selection(void);
1528 void update_mag_selection(void);
1529 void update_baro_selection(void);
1530 void update_airspeed_selection(void);
1532 // selected and preferred sensor instances. We separate selected
1533 // from preferred so that calcGpsGoodToAlign() can ensure the
1534 // preferred sensor is ready. Note that magSelectIndex is used for
1535 // compass selection
1536 uint8_t selected_gps;
1537 uint8_t preferred_gps;
1538 uint8_t selected_baro;
1539 uint8_t selected_airspeed;
1541 // source reset handling
1542 AP_NavEKF_Source::SourceXY posxy_source_last; // horizontal position source on previous iteration (used to detect a changes)
1543 bool posxy_source_reset; // true when the horizontal position source has changed but the position has not yet been reset
1544 AP_NavEKF_Source::SourceYaw yaw_source_last; // yaw source on previous iteration (used to detect a change)
1545 bool yaw_source_reset; // true when the yaw source has changed but the yaw has not yet been reset
1547 // logging functions shared by cores:
1548 void Log_Write_XKF1(uint64_t time_us) const;
1549 void Log_Write_XKF2(uint64_t time_us) const;
1550 void Log_Write_XKF3(uint64_t time_us) const;
1551 void Log_Write_XKF4(uint64_t time_us) const;
1552 void Log_Write_XKF5(uint64_t time_us) const;
1553 void Log_Write_XKFS(uint64_t time_us) const;
1554 void Log_Write_Quaternion(uint64_t time_us) const;
1555 void Log_Write_Beacon(uint64_t time_us);
1556 void Log_Write_BodyOdom(uint64_t time_us);
1557 void Log_Write_State_Variances(uint64_t time_us);
1558 void Log_Write_Timing(uint64_t time_us);
1559 void Log_Write_GSF(uint64_t time_us);