AP_NavEKF3.h 32 KB

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