AP_NavEKF2_core.h 63 KB

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