AP_NavEKF3_core.h 69 KB

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