AP_NavEKF2.cpp 67 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_NavEKF2_core.h"
  3. #include <AP_Vehicle/AP_Vehicle.h>
  4. #include <GCS_MAVLink/GCS.h>
  5. #include <AP_Logger/AP_Logger.h>
  6. #include <AP_GPS/AP_GPS.h>
  7. #include <new>
  8. /*
  9. parameter defaults for different types of vehicle. The
  10. APM_BUILD_DIRECTORY is taken from the main vehicle directory name
  11. where the code is built.
  12. */
  13. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_Replay)
  14. // copter defaults
  15. #define VELNE_M_NSE_DEFAULT 0.5f
  16. #define VELD_M_NSE_DEFAULT 0.7f
  17. #define POSNE_M_NSE_DEFAULT 1.0f
  18. #define ALT_M_NSE_DEFAULT 3.0f
  19. #define MAG_M_NSE_DEFAULT 0.05f
  20. #define GYRO_P_NSE_DEFAULT 3.0E-02f
  21. #define ACC_P_NSE_DEFAULT 6.0E-01f
  22. #define GBIAS_P_NSE_DEFAULT 1.0E-04f
  23. #define GSCALE_P_NSE_DEFAULT 5.0E-04f
  24. #define ABIAS_P_NSE_DEFAULT 5.0E-03f
  25. #define MAGB_P_NSE_DEFAULT 1.0E-04f
  26. #define MAGE_P_NSE_DEFAULT 1.0E-03f
  27. #define VEL_I_GATE_DEFAULT 500
  28. #define POS_I_GATE_DEFAULT 500
  29. #define HGT_I_GATE_DEFAULT 500
  30. #define MAG_I_GATE_DEFAULT 300
  31. #define MAG_CAL_DEFAULT 3
  32. #define GLITCH_RADIUS_DEFAULT 25
  33. #define FLOW_MEAS_DELAY 10
  34. #define FLOW_M_NSE_DEFAULT 0.25f
  35. #define FLOW_I_GATE_DEFAULT 300
  36. #define CHECK_SCALER_DEFAULT 100
  37. #define FLOW_USE_DEFAULT 1
  38. #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
  39. // rover defaults
  40. #define VELNE_M_NSE_DEFAULT 0.5f
  41. #define VELD_M_NSE_DEFAULT 0.7f
  42. #define POSNE_M_NSE_DEFAULT 1.0f
  43. #define ALT_M_NSE_DEFAULT 3.0f
  44. #define MAG_M_NSE_DEFAULT 0.05f
  45. #define GYRO_P_NSE_DEFAULT 3.0E-02f
  46. #define ACC_P_NSE_DEFAULT 6.0E-01f
  47. #define GBIAS_P_NSE_DEFAULT 1.0E-04f
  48. #define GSCALE_P_NSE_DEFAULT 5.0E-04f
  49. #define ABIAS_P_NSE_DEFAULT 5.0E-03f
  50. #define MAGB_P_NSE_DEFAULT 1.0E-04f
  51. #define MAGE_P_NSE_DEFAULT 1.0E-03f
  52. #define VEL_I_GATE_DEFAULT 500
  53. #define POS_I_GATE_DEFAULT 500
  54. #define HGT_I_GATE_DEFAULT 500
  55. #define MAG_I_GATE_DEFAULT 300
  56. #define MAG_CAL_DEFAULT 2
  57. #define GLITCH_RADIUS_DEFAULT 25
  58. #define FLOW_MEAS_DELAY 10
  59. #define FLOW_M_NSE_DEFAULT 0.25f
  60. #define FLOW_I_GATE_DEFAULT 300
  61. #define CHECK_SCALER_DEFAULT 100
  62. #define FLOW_USE_DEFAULT 1
  63. #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  64. // plane defaults
  65. #define VELNE_M_NSE_DEFAULT 0.5f
  66. #define VELD_M_NSE_DEFAULT 0.7f
  67. #define POSNE_M_NSE_DEFAULT 1.0f
  68. #define ALT_M_NSE_DEFAULT 3.0f
  69. #define MAG_M_NSE_DEFAULT 0.05f
  70. #define GYRO_P_NSE_DEFAULT 3.0E-02f
  71. #define ACC_P_NSE_DEFAULT 6.0E-01f
  72. #define GBIAS_P_NSE_DEFAULT 1.0E-04f
  73. #define GSCALE_P_NSE_DEFAULT 5.0E-04f
  74. #define ABIAS_P_NSE_DEFAULT 5.0E-03f
  75. #define MAGB_P_NSE_DEFAULT 1.0E-04f
  76. #define MAGE_P_NSE_DEFAULT 1.0E-03f
  77. #define VEL_I_GATE_DEFAULT 500
  78. #define POS_I_GATE_DEFAULT 500
  79. #define HGT_I_GATE_DEFAULT 500
  80. #define MAG_I_GATE_DEFAULT 300
  81. #define MAG_CAL_DEFAULT 0
  82. #define GLITCH_RADIUS_DEFAULT 25
  83. #define FLOW_MEAS_DELAY 10
  84. #define FLOW_M_NSE_DEFAULT 0.15f
  85. #define FLOW_I_GATE_DEFAULT 500
  86. #define CHECK_SCALER_DEFAULT 150
  87. #define FLOW_USE_DEFAULT 2
  88. #else
  89. // build type not specified, use copter defaults
  90. #define VELNE_M_NSE_DEFAULT 0.5f
  91. #define VELD_M_NSE_DEFAULT 0.7f
  92. #define POSNE_M_NSE_DEFAULT 1.0f
  93. #define ALT_M_NSE_DEFAULT 3.0f
  94. #define MAG_M_NSE_DEFAULT 0.05f
  95. #define GYRO_P_NSE_DEFAULT 3.0E-02f
  96. #define ACC_P_NSE_DEFAULT 6.0E-01f
  97. #define GBIAS_P_NSE_DEFAULT 1.0E-04f
  98. #define GSCALE_P_NSE_DEFAULT 5.0E-04f
  99. #define ABIAS_P_NSE_DEFAULT 5.0E-03f
  100. #define MAGB_P_NSE_DEFAULT 1.0E-04f
  101. #define MAGE_P_NSE_DEFAULT 1.0E-03f
  102. #define VEL_I_GATE_DEFAULT 500
  103. #define POS_I_GATE_DEFAULT 500
  104. #define HGT_I_GATE_DEFAULT 500
  105. #define MAG_I_GATE_DEFAULT 300
  106. #define MAG_CAL_DEFAULT 3
  107. #define GLITCH_RADIUS_DEFAULT 25
  108. #define FLOW_MEAS_DELAY 10
  109. #define FLOW_M_NSE_DEFAULT 0.25f
  110. #define FLOW_I_GATE_DEFAULT 300
  111. #define CHECK_SCALER_DEFAULT 100
  112. #define FLOW_USE_DEFAULT 1
  113. #endif // APM_BUILD_DIRECTORY
  114. extern const AP_HAL::HAL& hal;
  115. // Define tuning parameters
  116. const AP_Param::GroupInfo NavEKF2::var_info[] = {
  117. // @Param: ENABLE
  118. // @DisplayName: Enable EKF2
  119. // @Description: This enables EKF2. Enabling EKF2 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_TYPE=2. A reboot or restart will need to be performed after changing the value of EK2_ENABLE for it to take effect.
  120. // @Values: 0:Disabled, 1:Enabled
  121. // @User: Advanced
  122. // @RebootRequired: True
  123. AP_GROUPINFO_FLAGS("ENABLE", 0, NavEKF2, _enable, 1, AP_PARAM_FLAG_ENABLE),
  124. // GPS measurement parameters
  125. // @Param: GPS_TYPE
  126. // @DisplayName: GPS mode control
  127. // @Description: This controls use of GPS measurements : 0 = use 3D velocity & 2D position, 1 = use 2D velocity and 2D position, 2 = use 2D position, 3 = Inhibit GPS use - this can be useful when flying with an optical flow sensor in an environment where GPS quality is poor and subject to large multipath errors.
  128. // @Values: 0:GPS 3D Vel and 2D Pos, 1:GPS 2D vel and 2D pos, 2:GPS 2D pos, 3:No GPS
  129. // @User: Advanced
  130. AP_GROUPINFO("GPS_TYPE", 1, NavEKF2, _fusionModeGPS, 0),
  131. // @Param: VELNE_M_NSE
  132. // @DisplayName: GPS horizontal velocity measurement noise (m/s)
  133. // @Description: This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS horizontal velocity measurements.
  134. // @Range: 0.05 5.0
  135. // @Increment: 0.05
  136. // @User: Advanced
  137. // @Units: m/s
  138. AP_GROUPINFO("VELNE_M_NSE", 2, NavEKF2, _gpsHorizVelNoise, VELNE_M_NSE_DEFAULT),
  139. // @Param: VELD_M_NSE
  140. // @DisplayName: GPS vertical velocity measurement noise (m/s)
  141. // @Description: This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS vertical velocity measurements.
  142. // @Range: 0.05 5.0
  143. // @Increment: 0.05
  144. // @User: Advanced
  145. // @Units: m/s
  146. AP_GROUPINFO("VELD_M_NSE", 3, NavEKF2, _gpsVertVelNoise, VELD_M_NSE_DEFAULT),
  147. // @Param: VEL_I_GATE
  148. // @DisplayName: GPS velocity innovation gate size
  149. // @Description: This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
  150. // @Range: 100 1000
  151. // @Increment: 25
  152. // @User: Advanced
  153. AP_GROUPINFO("VEL_I_GATE", 4, NavEKF2, _gpsVelInnovGate, VEL_I_GATE_DEFAULT),
  154. // @Param: POSNE_M_NSE
  155. // @DisplayName: GPS horizontal position measurement noise (m)
  156. // @Description: This sets the GPS horizontal position or external navigation system position observation noise. Increasing it reduces the weighting of GPS horizontal position or external navigation system position measurements.
  157. // @Range: 0.1 10.0
  158. // @Increment: 0.1
  159. // @User: Advanced
  160. // @Units: m
  161. AP_GROUPINFO("POSNE_M_NSE", 5, NavEKF2, _gpsHorizPosNoise, POSNE_M_NSE_DEFAULT),
  162. // @Param: POS_I_GATE
  163. // @DisplayName: GPS position measurement gate size
  164. // @Description: This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  165. // @Range: 100 1000
  166. // @Increment: 25
  167. // @User: Advanced
  168. AP_GROUPINFO("POS_I_GATE", 6, NavEKF2, _gpsPosInnovGate, POS_I_GATE_DEFAULT),
  169. // @Param: GLITCH_RAD
  170. // @DisplayName: GPS glitch radius gate size (m)
  171. // @Description: This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position.
  172. // @Range: 10 100
  173. // @Increment: 5
  174. // @User: Advanced
  175. // @Units: m
  176. AP_GROUPINFO("GLITCH_RAD", 7, NavEKF2, _gpsGlitchRadiusMax, GLITCH_RADIUS_DEFAULT),
  177. // 8 was used for GPS_DELAY
  178. // Height measurement parameters
  179. // @Param: ALT_SOURCE
  180. // @DisplayName: Primary altitude sensor source
  181. // @Description: Primary height sensor used by the EKF. If the selected option cannot be used, baro is used. 1 uses the range finder and only with optical flow navigation (EK2_GPS_TYPE = 3), Do not use "1" for terrain following. NOTE: the EK2_RNG_USE_HGT parameter can be used to switch to range-finder when close to the ground.
  182. // @Values: 0:Use Baro, 1:Use Range Finder, 2:Use GPS, 3:Use Range Beacon
  183. // @User: Advanced
  184. // @RebootRequired: True
  185. AP_GROUPINFO("ALT_SOURCE", 9, NavEKF2, _altSource, 0),
  186. // @Param: ALT_M_NSE
  187. // @DisplayName: Altitude measurement noise (m)
  188. // @Description: This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors.
  189. // @Range: 0.1 10.0
  190. // @Increment: 0.1
  191. // @User: Advanced
  192. // @Units: m
  193. AP_GROUPINFO("ALT_M_NSE", 10, NavEKF2, _baroAltNoise, ALT_M_NSE_DEFAULT),
  194. // @Param: HGT_I_GATE
  195. // @DisplayName: Height measurement gate size
  196. // @Description: This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  197. // @Range: 100 1000
  198. // @Increment: 25
  199. // @User: Advanced
  200. AP_GROUPINFO("HGT_I_GATE", 11, NavEKF2, _hgtInnovGate, HGT_I_GATE_DEFAULT),
  201. // @Param: HGT_DELAY
  202. // @DisplayName: Height measurement delay (msec)
  203. // @Description: This is the number of msec that the Height measurements lag behind the inertial measurements.
  204. // @Range: 0 250
  205. // @Increment: 10
  206. // @User: Advanced
  207. // @Units: ms
  208. // @RebootRequired: True
  209. AP_GROUPINFO("HGT_DELAY", 12, NavEKF2, _hgtDelay_ms, 60),
  210. // Magnetometer measurement parameters
  211. // @Param: MAG_M_NSE
  212. // @DisplayName: Magnetometer measurement noise (Gauss)
  213. // @Description: This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements.
  214. // @Range: 0.01 0.5
  215. // @Increment: 0.01
  216. // @User: Advanced
  217. // @Units: Gauss
  218. AP_GROUPINFO("MAG_M_NSE", 13, NavEKF2, _magNoise, MAG_M_NSE_DEFAULT),
  219. // @Param: MAG_CAL
  220. // @DisplayName: Magnetometer default fusion mode
  221. // @Description: This determines when the filter will use the 3-axis magnetometer fusion model that estimates both earth and body fixed magnetic field states and when it will use a simpler magnetic heading fusion model that does not use magnetic field states. The 3-axis magnetometer fusion is only suitable for use when the external magnetic field environment is stable. EK2_MAG_CAL = 0 uses heading fusion on ground, 3-axis fusion in-flight, and is the default setting for Plane users. EK2_MAG_CAL = 1 uses 3-axis fusion only when manoeuvring. EK2_MAG_CAL = 2 uses heading fusion at all times, is recommended if the external magnetic field is varying and is the default for rovers. EK2_MAG_CAL = 3 uses heading fusion on the ground and 3-axis fusion after the first in-air field and yaw reset has completed, and is the default for copters. EK2_MAG_CAL = 4 uses 3-axis fusion at all times. NOTE : Use of simple heading magnetometer fusion makes vehicle compass calibration and alignment errors harder for the EKF to detect which reduces the sensitivity of the Copter EKF failsafe algorithm. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK2_MAG_MASK parameter.
  222. // @Values: 0:When flying,1:When manoeuvring,2:Never,3:After first climb yaw reset,4:Always
  223. // @User: Advanced
  224. AP_GROUPINFO("MAG_CAL", 14, NavEKF2, _magCal, MAG_CAL_DEFAULT),
  225. // @Param: MAG_I_GATE
  226. // @DisplayName: Magnetometer measurement gate size
  227. // @Description: This sets the percentage number of standard deviations applied to the magnetometer measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  228. // @Range: 100 1000
  229. // @Increment: 25
  230. // @User: Advanced
  231. AP_GROUPINFO("MAG_I_GATE", 15, NavEKF2, _magInnovGate, MAG_I_GATE_DEFAULT),
  232. // Airspeed measurement parameters
  233. // @Param: EAS_M_NSE
  234. // @DisplayName: Equivalent airspeed measurement noise (m/s)
  235. // @Description: This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements.
  236. // @Range: 0.5 5.0
  237. // @Increment: 0.1
  238. // @User: Advanced
  239. // @Units: m/s
  240. AP_GROUPINFO("EAS_M_NSE", 16, NavEKF2, _easNoise, 1.4f),
  241. // @Param: EAS_I_GATE
  242. // @DisplayName: Airspeed measurement gate size
  243. // @Description: This sets the percentage number of standard deviations applied to the airspeed measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  244. // @Range: 100 1000
  245. // @Increment: 25
  246. // @User: Advanced
  247. AP_GROUPINFO("EAS_I_GATE", 17, NavEKF2, _tasInnovGate, 400),
  248. // Rangefinder measurement parameters
  249. // @Param: RNG_M_NSE
  250. // @DisplayName: Range finder measurement noise (m)
  251. // @Description: This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
  252. // @Range: 0.1 10.0
  253. // @Increment: 0.1
  254. // @User: Advanced
  255. // @Units: m
  256. AP_GROUPINFO("RNG_M_NSE", 18, NavEKF2, _rngNoise, 0.5f),
  257. // @Param: RNG_I_GATE
  258. // @DisplayName: Range finder measurement gate size
  259. // @Description: This sets the percentage number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  260. // @Range: 100 1000
  261. // @Increment: 25
  262. // @User: Advanced
  263. AP_GROUPINFO("RNG_I_GATE", 19, NavEKF2, _rngInnovGate, 500),
  264. // Optical flow measurement parameters
  265. // @Param: MAX_FLOW
  266. // @DisplayName: Maximum valid optical flow rate
  267. // @Description: This sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
  268. // @Range: 1.0 4.0
  269. // @Increment: 0.1
  270. // @User: Advanced
  271. // @Units: rad/s
  272. AP_GROUPINFO("MAX_FLOW", 20, NavEKF2, _maxFlowRate, 2.5f),
  273. // @Param: FLOW_M_NSE
  274. // @DisplayName: Optical flow measurement noise (rad/s)
  275. // @Description: This is the RMS value of noise and errors in optical flow measurements. Increasing it reduces the weighting on these measurements.
  276. // @Range: 0.05 1.0
  277. // @Increment: 0.05
  278. // @User: Advanced
  279. // @Units: rad/s
  280. AP_GROUPINFO("FLOW_M_NSE", 21, NavEKF2, _flowNoise, FLOW_M_NSE_DEFAULT),
  281. // @Param: FLOW_I_GATE
  282. // @DisplayName: Optical Flow measurement gate size
  283. // @Description: This sets the percentage number of standard deviations applied to the optical flow innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  284. // @Range: 100 1000
  285. // @Increment: 25
  286. // @User: Advanced
  287. AP_GROUPINFO("FLOW_I_GATE", 22, NavEKF2, _flowInnovGate, FLOW_I_GATE_DEFAULT),
  288. // @Param: FLOW_DELAY
  289. // @DisplayName: Optical Flow measurement delay (msec)
  290. // @Description: This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
  291. // @Range: 0 127
  292. // @Increment: 10
  293. // @User: Advanced
  294. // @Units: ms
  295. // @RebootRequired: True
  296. AP_GROUPINFO("FLOW_DELAY", 23, NavEKF2, _flowDelay_ms, FLOW_MEAS_DELAY),
  297. // State and Covariance Predition Parameters
  298. // @Param: GYRO_P_NSE
  299. // @DisplayName: Rate gyro noise (rad/s)
  300. // @Description: This control disturbance noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
  301. // @Range: 0.0001 0.1
  302. // @Increment: 0.0001
  303. // @User: Advanced
  304. // @Units: rad/s
  305. AP_GROUPINFO("GYRO_P_NSE", 24, NavEKF2, _gyrNoise, GYRO_P_NSE_DEFAULT),
  306. // @Param: ACC_P_NSE
  307. // @DisplayName: Accelerometer noise (m/s^2)
  308. // @Description: This control disturbance noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
  309. // @Range: 0.01 1.0
  310. // @Increment: 0.01
  311. // @User: Advanced
  312. // @Units: m/s/s
  313. AP_GROUPINFO("ACC_P_NSE", 25, NavEKF2, _accNoise, ACC_P_NSE_DEFAULT),
  314. // @Param: GBIAS_P_NSE
  315. // @DisplayName: Rate gyro bias stability (rad/s/s)
  316. // @Description: This state process noise controls growth of the gyro delta angle bias state error estimate. Increasing it makes rate gyro bias estimation faster and noisier.
  317. // @Range: 0.00001 0.001
  318. // @User: Advanced
  319. // @Units: rad/s/s
  320. AP_GROUPINFO("GBIAS_P_NSE", 26, NavEKF2, _gyroBiasProcessNoise, GBIAS_P_NSE_DEFAULT),
  321. // @Param: GSCL_P_NSE
  322. // @DisplayName: Rate gyro scale factor stability (1/s)
  323. // @Description: This noise controls the rate of gyro scale factor learning. Increasing it makes rate gyro scale factor estimation faster and noisier.
  324. // @Range: 0.000001 0.001
  325. // @User: Advanced
  326. // @Units: Hz
  327. AP_GROUPINFO("GSCL_P_NSE", 27, NavEKF2, _gyroScaleProcessNoise, GSCALE_P_NSE_DEFAULT),
  328. // @Param: ABIAS_P_NSE
  329. // @DisplayName: Accelerometer bias stability (m/s^3)
  330. // @Description: This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
  331. // @Range: 0.00001 0.005
  332. // @User: Advanced
  333. // @Units: m/s/s/s
  334. AP_GROUPINFO("ABIAS_P_NSE", 28, NavEKF2, _accelBiasProcessNoise, ABIAS_P_NSE_DEFAULT),
  335. // 29 previously used for EK2_MAG_P_NSE parameter that has been replaced with EK2_MAGE_P_NSE and EK2_MAGB_P_NSE
  336. // @Param: WIND_P_NSE
  337. // @DisplayName: Wind velocity process noise (m/s^2)
  338. // @Description: This state process noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier.
  339. // @Range: 0.01 1.0
  340. // @Increment: 0.1
  341. // @User: Advanced
  342. // @Units: m/s/s
  343. AP_GROUPINFO("WIND_P_NSE", 30, NavEKF2, _windVelProcessNoise, 0.1f),
  344. // @Param: WIND_PSCALE
  345. // @DisplayName: Height rate to wind process noise scaler
  346. // @Description: This controls how much the process noise on the wind states is increased when gaining or losing altitude to take into account changes in wind speed and direction with altitude. Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind velocity estimation noiser.
  347. // @Range: 0.0 1.0
  348. // @Increment: 0.1
  349. // @User: Advanced
  350. AP_GROUPINFO("WIND_PSCALE", 31, NavEKF2, _wndVarHgtRateScale, 0.5f),
  351. // @Param: GPS_CHECK
  352. // @DisplayName: GPS preflight check
  353. // @Description: This is a 1 byte bitmap controlling which GPS preflight checks are performed. Set to 0 to bypass all checks. Set to 255 perform all checks. Set to 3 to check just the number of satellites and HDoP. Set to 31 for the most rigorous checks that will still allow checks to pass when the copter is moving, eg launch from a boat.
  354. // @Bitmask: 0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed
  355. // @User: Advanced
  356. AP_GROUPINFO("GPS_CHECK", 32, NavEKF2, _gpsCheck, 31),
  357. // @Param: IMU_MASK
  358. // @DisplayName: Bitmask of active IMUs
  359. // @Description: 1 byte bitmap of IMUs to use in EKF2. A separate instance of EKF2 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF2 will fail to start.
  360. // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
  361. // @User: Advanced
  362. // @RebootRequired: True
  363. AP_GROUPINFO("IMU_MASK", 33, NavEKF2, _imuMask, 3),
  364. // @Param: CHECK_SCALE
  365. // @DisplayName: GPS accuracy check scaler (%)
  366. // @Description: This scales the thresholds that are used to check GPS accuracy before it is used by the EKF. A value of 100 is the default. Values greater than 100 increase and values less than 100 reduce the maximum GPS error the EKF will accept. A value of 200 will double the allowable GPS error.
  367. // @Range: 50 200
  368. // @User: Advanced
  369. // @Units: %
  370. AP_GROUPINFO("CHECK_SCALE", 34, NavEKF2, _gpsCheckScaler, CHECK_SCALER_DEFAULT),
  371. // @Param: NOAID_M_NSE
  372. // @DisplayName: Non-GPS operation position uncertainty (m)
  373. // @Description: This sets the amount of position variation that the EKF allows for when operating without external measurements (eg GPS or optical flow). Increasing this parameter makes the EKF attitude estimate less sensitive to vehicle manoeuvres but more sensitive to IMU errors.
  374. // @Range: 0.5 50.0
  375. // @User: Advanced
  376. // @Units: m
  377. AP_GROUPINFO("NOAID_M_NSE", 35, NavEKF2, _noaidHorizNoise, 10.0f),
  378. // @Param: LOG_MASK
  379. // @DisplayName: EKF sensor logging IMU mask
  380. // @Description: This sets the IMU mask of sensors to do full logging for
  381. // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
  382. // @User: Advanced
  383. // @RebootRequired: True
  384. AP_GROUPINFO("LOG_MASK", 36, NavEKF2, _logging_mask, 1),
  385. // control of magentic yaw angle fusion
  386. // @Param: YAW_M_NSE
  387. // @DisplayName: Yaw measurement noise (rad)
  388. // @Description: This is the RMS value of noise in yaw measurements from the magnetometer. Increasing it reduces the weighting on these measurements.
  389. // @Range: 0.05 1.0
  390. // @Increment: 0.05
  391. // @User: Advanced
  392. // @Units: rad
  393. AP_GROUPINFO("YAW_M_NSE", 37, NavEKF2, _yawNoise, 0.5f),
  394. // @Param: YAW_I_GATE
  395. // @DisplayName: Yaw measurement gate size
  396. // @Description: This sets the percentage number of standard deviations applied to the magnetometer yaw measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  397. // @Range: 100 1000
  398. // @Increment: 25
  399. // @User: Advanced
  400. AP_GROUPINFO("YAW_I_GATE", 38, NavEKF2, _yawInnovGate, 300),
  401. // @Param: TAU_OUTPUT
  402. // @DisplayName: Output complementary filter time constant (centi-sec)
  403. // @Description: Sets the time constant of the output complementary filter/predictor in centi-seconds.
  404. // @Range: 10 50
  405. // @Increment: 5
  406. // @User: Advanced
  407. // @Units: cs
  408. AP_GROUPINFO("TAU_OUTPUT", 39, NavEKF2, _tauVelPosOutput, 25),
  409. // @Param: MAGE_P_NSE
  410. // @DisplayName: Earth magnetic field process noise (gauss/s)
  411. // @Description: This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier.
  412. // @Range: 0.00001 0.01
  413. // @User: Advanced
  414. // @Units: Gauss/s
  415. AP_GROUPINFO("MAGE_P_NSE", 40, NavEKF2, _magEarthProcessNoise, MAGE_P_NSE_DEFAULT),
  416. // @Param: MAGB_P_NSE
  417. // @DisplayName: Body magnetic field process noise (gauss/s)
  418. // @Description: This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier.
  419. // @Range: 0.00001 0.01
  420. // @User: Advanced
  421. // @Units: Gauss/s
  422. AP_GROUPINFO("MAGB_P_NSE", 41, NavEKF2, _magBodyProcessNoise, MAGB_P_NSE_DEFAULT),
  423. // @Param: RNG_USE_HGT
  424. // @DisplayName: Range finder switch height percentage
  425. // @Description: Range finder can be used as the primary height source when below this percentage of its maximum range (see RNGFND_MAX_CM). Set to -1 when EK2_ALT_SOURCE is not set to range finder. This is not for terrain following.
  426. // @Range: -1 70
  427. // @Increment: 1
  428. // @User: Advanced
  429. // @Units: %
  430. AP_GROUPINFO("RNG_USE_HGT", 42, NavEKF2, _useRngSwHgt, -1),
  431. // @Param: TERR_GRAD
  432. // @DisplayName: Maximum terrain gradient
  433. // @Description: Specifies the maximum gradient of the terrain below the vehicle assumed when it is fusing range finder or optical flow to estimate terrain height.
  434. // @Range: 0 0.2
  435. // @Increment: 0.01
  436. // @User: Advanced
  437. AP_GROUPINFO("TERR_GRAD", 43, NavEKF2, _terrGradMax, 0.1f),
  438. // @Param: BCN_M_NSE
  439. // @DisplayName: Range beacon measurement noise (m)
  440. // @Description: This is the RMS value of noise in the range beacon measurement. Increasing it reduces the weighting on this measurement.
  441. // @Range: 0.1 10.0
  442. // @Increment: 0.1
  443. // @User: Advanced
  444. // @Units: m
  445. AP_GROUPINFO("BCN_M_NSE", 44, NavEKF2, _rngBcnNoise, 1.0f),
  446. // @Param: BCN_I_GTE
  447. // @DisplayName: Range beacon measurement gate size
  448. // @Description: This sets the percentage number of standard deviations applied to the range beacon measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
  449. // @Range: 100 1000
  450. // @Increment: 25
  451. // @User: Advanced
  452. AP_GROUPINFO("BCN_I_GTE", 45, NavEKF2, _rngBcnInnovGate, 500),
  453. // @Param: BCN_DELAY
  454. // @DisplayName: Range beacon measurement delay (msec)
  455. // @Description: This is the number of msec that the range beacon measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
  456. // @Range: 0 127
  457. // @Increment: 10
  458. // @User: Advanced
  459. // @Units: ms
  460. // @RebootRequired: True
  461. AP_GROUPINFO("BCN_DELAY", 46, NavEKF2, _rngBcnDelay_ms, 50),
  462. // @Param: RNG_USE_SPD
  463. // @DisplayName: Range finder max ground speed
  464. // @Description: The range finder will not be used as the primary height source when the horizontal ground speed is greater than this value.
  465. // @Range: 2.0 6.0
  466. // @Increment: 0.5
  467. // @User: Advanced
  468. // @Units: m/s
  469. AP_GROUPINFO("RNG_USE_SPD", 47, NavEKF2, _useRngSwSpd, 2.0f),
  470. // @Param: MAG_MASK
  471. // @DisplayName: Bitmask of active EKF cores that will always use heading fusion
  472. // @Description: 1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
  473. // @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
  474. // @User: Advanced
  475. // @RebootRequired: True
  476. AP_GROUPINFO("MAG_MASK", 48, NavEKF2, _magMask, 0),
  477. // @Param: OGN_HGT_MASK
  478. // @DisplayName: Bitmask control of EKF reference height correction
  479. // @Description: When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time. The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits. The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position or to the reported EKF origin height (default).
  480. // @Bitmask: 0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position
  481. // @User: Advanced
  482. // @RebootRequired: True
  483. AP_GROUPINFO("OGN_HGT_MASK", 49, NavEKF2, _originHgtMode, 0),
  484. // @Param: EXTNAV_DELAY
  485. // @DisplayName: external navigation system measurement delay (msec)
  486. // @Description: This is the number of msec that the external navigation system measurements lag behind the inertial measurements.
  487. // @Range: 0 127
  488. // @Increment: 1
  489. // @User: Advanced
  490. // @Units: ms
  491. // @RebootRequired: True
  492. AP_GROUPINFO("EXTNAV_DELAY", 50, NavEKF2, _extnavDelay_ms, 10),
  493. // @Param: FLOW_USE
  494. // @DisplayName: Optical flow use bitmask
  495. // @Description: Controls if the optical flow data is fused into the 24-state navigation estimator OR the 1-state terrain height estimator.
  496. // @User: Advanced
  497. // @Values: 0:None,1:Navigation,2:Terrain
  498. // @RebootRequired: True
  499. AP_GROUPINFO("FLOW_USE", 51, NavEKF2, _flowUse, FLOW_USE_DEFAULT),
  500. // @Param: MAG_EF_LIM
  501. // @DisplayName: EarthField error limit
  502. // @Description: This limits the difference between the learned earth magnetic field and the earth field from the world magnetic model tables. A value of zero means to disable the use of the WMM tables.
  503. // @User: Advanced
  504. // @Range: 0 500
  505. // @Units: mGauss
  506. AP_GROUPINFO("MAG_EF_LIM", 52, NavEKF2, _mag_ef_limit, 50),
  507. AP_GROUPEND
  508. };
  509. NavEKF2::NavEKF2(const AP_AHRS *ahrs, const RangeFinder &rng) :
  510. _ahrs(ahrs),
  511. _rng(rng)
  512. {
  513. AP_Param::setup_object_defaults(this, var_info);
  514. }
  515. /*
  516. see if we should log some sensor data
  517. */
  518. void NavEKF2::check_log_write(void)
  519. {
  520. if (!have_ekf_logging()) {
  521. return;
  522. }
  523. if (logging.log_compass) {
  524. AP::logger().Write_Compass(imuSampleTime_us);
  525. logging.log_compass = false;
  526. }
  527. if (logging.log_baro) {
  528. AP::logger().Write_Baro(imuSampleTime_us);
  529. logging.log_baro = false;
  530. }
  531. if (logging.log_imu) {
  532. AP::logger().Write_IMUDT(imuSampleTime_us, _logging_mask.get());
  533. logging.log_imu = false;
  534. }
  535. // this is an example of an ad-hoc log in EKF
  536. // AP::logger().Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f);
  537. }
  538. // Initialise the filter
  539. bool NavEKF2::InitialiseFilter(void)
  540. {
  541. if (_enable == 0) {
  542. return false;
  543. }
  544. const AP_InertialSensor &ins = AP::ins();
  545. imuSampleTime_us = AP_HAL::micros64();
  546. // remember expected frame time
  547. _frameTimeUsec = 1e6 / ins.get_sample_rate();
  548. // expected number of IMU frames per prediction
  549. _framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
  550. // see if we will be doing logging
  551. AP_Logger *logger = AP_Logger::get_singleton();
  552. if (logger != nullptr) {
  553. logging.enabled = logger->log_replay();
  554. }
  555. if (core == nullptr) {
  556. // don't run multiple filters for 1 IMU
  557. uint8_t mask = (1U<<ins.get_accel_count())-1;
  558. _imuMask.set(_imuMask.get() & mask);
  559. // count IMUs from mask
  560. num_cores = 0;
  561. for (uint8_t i=0; i<7; i++) {
  562. if (_imuMask & (1U<<i)) {
  563. num_cores++;
  564. }
  565. }
  566. // check if there is enough memory to create the EKF cores
  567. if (hal.util->available_memory() < sizeof(NavEKF2_core)*num_cores + 4096) {
  568. gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: not enough memory");
  569. _enable.set(0);
  570. return false;
  571. }
  572. // try to allocate from CCM RAM, fallback to Normal RAM if not available or full
  573. core = (NavEKF2_core*)hal.util->malloc_type(sizeof(NavEKF2_core)*num_cores, AP_HAL::Util::MEM_FAST);
  574. if (core == nullptr) {
  575. _enable.set(0);
  576. gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: allocation failed");
  577. return false;
  578. }
  579. //Call Constructors on all cores
  580. for (uint8_t i = 0; i < num_cores; i++) {
  581. new (&core[i]) NavEKF2_core(this);
  582. }
  583. // set the IMU index for the cores
  584. num_cores = 0;
  585. for (uint8_t i=0; i<7; i++) {
  586. if (_imuMask & (1U<<i)) {
  587. if(!core[num_cores].setup_core(i, num_cores)) {
  588. return false;
  589. }
  590. num_cores++;
  591. }
  592. }
  593. // Set the primary initially to be the lowest index
  594. primary = 0;
  595. }
  596. // invalidate shared origin
  597. common_origin_valid = false;
  598. // initialise the cores. We return success only if all cores
  599. // initialise successfully
  600. bool ret = true;
  601. for (uint8_t i=0; i<num_cores; i++) {
  602. ret &= core[i].InitialiseFilterBootstrap();
  603. }
  604. // zero the structs used capture reset events
  605. memset(&yaw_reset_data, 0, sizeof(yaw_reset_data));
  606. memset((void *)&pos_reset_data, 0, sizeof(pos_reset_data));
  607. memset(&pos_down_reset_data, 0, sizeof(pos_down_reset_data));
  608. check_log_write();
  609. return ret;
  610. }
  611. // Update Filter States - this should be called whenever new IMU data is available
  612. void NavEKF2::UpdateFilter(void)
  613. {
  614. if (!core) {
  615. return;
  616. }
  617. imuSampleTime_us = AP_HAL::micros64();
  618. const AP_InertialSensor &ins = AP::ins();
  619. bool statePredictEnabled[num_cores];
  620. for (uint8_t i=0; i<num_cores; i++) {
  621. // if we have not overrun by more than 3 IMU frames, and we
  622. // have already used more than 1/3 of the CPU budget for this
  623. // loop then suppress the prediction step. This allows
  624. // multiple EKF instances to cooperate on scheduling
  625. if (core[i].getFramesSincePredict() < (_framesPerPrediction+3) &&
  626. (AP_HAL::micros() - ins.get_last_update_usec()) > _frameTimeUsec/3) {
  627. statePredictEnabled[i] = false;
  628. } else {
  629. statePredictEnabled[i] = true;
  630. }
  631. core[i].UpdateFilter(statePredictEnabled[i]);
  632. }
  633. // If the current core selected has a bad error score or is unhealthy, switch to a healthy core with the lowest fault score
  634. // Don't start running the check until the primary core has started returned healthy for at least 10 seconds to avoid switching
  635. // due to initial alignment fluctuations and race conditions
  636. if (!runCoreSelection) {
  637. static uint64_t lastUnhealthyTime_us = 0;
  638. if (!core[primary].healthy() || lastUnhealthyTime_us == 0) {
  639. lastUnhealthyTime_us = imuSampleTime_us;
  640. }
  641. runCoreSelection = (imuSampleTime_us - lastUnhealthyTime_us) > 1E7;
  642. }
  643. float primaryErrorScore = core[primary].errorScore();
  644. if ((primaryErrorScore > 1.0f || !core[primary].healthy()) && runCoreSelection) {
  645. float lowestErrorScore = 0.67f * primaryErrorScore;
  646. uint8_t newPrimaryIndex = primary; // index for new primary
  647. for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
  648. if (coreIndex != primary) {
  649. // an alternative core is available for selection only if healthy and if states have been updated on this time step
  650. bool altCoreAvailable = core[coreIndex].healthy() && statePredictEnabled[coreIndex];
  651. // If the primary core is unhealthy and another core is available, then switch now
  652. // If the primary core is still healthy,then switching is optional and will only be done if
  653. // a core with a significantly lower error score can be found
  654. float altErrorScore = core[coreIndex].errorScore();
  655. if (altCoreAvailable && (!core[newPrimaryIndex].healthy() || altErrorScore < lowestErrorScore)) {
  656. newPrimaryIndex = coreIndex;
  657. lowestErrorScore = altErrorScore;
  658. }
  659. }
  660. }
  661. // update the yaw and position reset data to capture changes due to the lane switch
  662. if (newPrimaryIndex != primary) {
  663. updateLaneSwitchYawResetData(newPrimaryIndex, primary);
  664. updateLaneSwitchPosResetData(newPrimaryIndex, primary);
  665. updateLaneSwitchPosDownResetData(newPrimaryIndex, primary);
  666. primary = newPrimaryIndex;
  667. lastLaneSwitch_ms = AP_HAL::millis();
  668. }
  669. }
  670. if (primary != 0 && core[0].healthy() && !hal.util->get_soft_armed()) {
  671. // when on the ground and disarmed force the first lane. This
  672. // avoids us ending with with a lottery for which IMU is used
  673. // in each flight. Otherwise the alignment of the timing of
  674. // the lane updates with the timing of GPS updates can lead to
  675. // a lane other than the first one being used as primary for
  676. // some flights. As different IMUs may have quite different
  677. // noise characteristics this leads to inconsistent
  678. // performance
  679. primary = 0;
  680. }
  681. check_log_write();
  682. }
  683. /*
  684. check if switching lanes will reduce the normalised
  685. innovations. This is called when the vehicle code is about to
  686. trigger an EKF failsafe, and it would like to avoid that by
  687. using a different EKF lane
  688. */
  689. void NavEKF2::checkLaneSwitch(void)
  690. {
  691. uint32_t now = AP_HAL::millis();
  692. if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) {
  693. // don't switch twice in 5 seconds
  694. return;
  695. }
  696. float primaryErrorScore = core[primary].errorScore();
  697. float lowestErrorScore = primaryErrorScore;
  698. uint8_t newPrimaryIndex = primary;
  699. for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
  700. if (coreIndex != primary) {
  701. // an alternative core is available for selection only if healthy and if states have been updated on this time step
  702. bool altCoreAvailable = core[coreIndex].healthy();
  703. float altErrorScore = core[coreIndex].errorScore();
  704. if (altCoreAvailable &&
  705. altErrorScore < lowestErrorScore &&
  706. altErrorScore < 0.9) {
  707. newPrimaryIndex = coreIndex;
  708. lowestErrorScore = altErrorScore;
  709. }
  710. }
  711. }
  712. // update the yaw and position reset data to capture changes due to the lane switch
  713. if (newPrimaryIndex != primary) {
  714. updateLaneSwitchYawResetData(newPrimaryIndex, primary);
  715. updateLaneSwitchPosResetData(newPrimaryIndex, primary);
  716. updateLaneSwitchPosDownResetData(newPrimaryIndex, primary);
  717. primary = newPrimaryIndex;
  718. lastLaneSwitch_ms = now;
  719. gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: lane switch %u", primary);
  720. }
  721. }
  722. // Check basic filter health metrics and return a consolidated health status
  723. bool NavEKF2::healthy(void) const
  724. {
  725. if (!core) {
  726. return false;
  727. }
  728. return core[primary].healthy();
  729. }
  730. bool NavEKF2::all_cores_healthy(void) const
  731. {
  732. if (!core) {
  733. return false;
  734. }
  735. for (uint8_t i = 0; i < num_cores; i++) {
  736. if (!core[i].healthy()) {
  737. return false;
  738. }
  739. }
  740. return true;
  741. }
  742. // returns the index of the primary core
  743. // return -1 if no primary core selected
  744. int8_t NavEKF2::getPrimaryCoreIndex(void) const
  745. {
  746. if (!core) {
  747. return -1;
  748. }
  749. return primary;
  750. }
  751. // returns the index of the IMU of the primary core
  752. // return -1 if no primary core selected
  753. int8_t NavEKF2::getPrimaryCoreIMUIndex(void) const
  754. {
  755. if (!core) {
  756. return -1;
  757. }
  758. return core[primary].getIMUIndex();
  759. }
  760. // Write the last calculated NE position relative to the reference point (m).
  761. // If a calculated solution is not available, use the best available data and return false
  762. // If false returned, do not use for flight control
  763. bool NavEKF2::getPosNE(int8_t instance, Vector2f &posNE) const
  764. {
  765. if (instance < 0 || instance >= num_cores) instance = primary;
  766. if (!core) {
  767. return false;
  768. }
  769. return core[instance].getPosNE(posNE);
  770. }
  771. // Write the last calculated D position relative to the reference point (m).
  772. // If a calculated solution is not available, use the best available data and return false
  773. // If false returned, do not use for flight control
  774. bool NavEKF2::getPosD(int8_t instance, float &posD) const
  775. {
  776. if (instance < 0 || instance >= num_cores) instance = primary;
  777. if (!core) {
  778. return false;
  779. }
  780. return core[instance].getPosD(posD);
  781. }
  782. // return NED velocity in m/s
  783. void NavEKF2::getVelNED(int8_t instance, Vector3f &vel) const
  784. {
  785. if (instance < 0 || instance >= num_cores) instance = primary;
  786. if (core) {
  787. core[instance].getVelNED(vel);
  788. }
  789. }
  790. // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
  791. float NavEKF2::getPosDownDerivative(int8_t instance) const
  792. {
  793. if (instance < 0 || instance >= num_cores) instance = primary;
  794. // return the value calculated from a complementary filter applied to the EKF height and vertical acceleration
  795. if (core) {
  796. return core[instance].getPosDownDerivative();
  797. }
  798. return 0.0f;
  799. }
  800. // This returns the specific forces in the NED frame
  801. void NavEKF2::getAccelNED(Vector3f &accelNED) const
  802. {
  803. if (core) {
  804. core[primary].getAccelNED(accelNED);
  805. }
  806. }
  807. // return body axis gyro bias estimates in rad/sec
  808. void NavEKF2::getGyroBias(int8_t instance, Vector3f &gyroBias) const
  809. {
  810. if (instance < 0 || instance >= num_cores) instance = primary;
  811. if (core) {
  812. core[instance].getGyroBias(gyroBias);
  813. }
  814. }
  815. // return body axis gyro scale factor error as a percentage
  816. void NavEKF2::getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const
  817. {
  818. if (instance < 0 || instance >= num_cores) instance = primary;
  819. if (core) {
  820. core[instance].getGyroScaleErrorPercentage(gyroScale);
  821. }
  822. }
  823. // return tilt error convergence metric for the specified instance
  824. void NavEKF2::getTiltError(int8_t instance, float &ang) const
  825. {
  826. if (instance < 0 || instance >= num_cores) instance = primary;
  827. if (core) {
  828. core[instance].getTiltError(ang);
  829. }
  830. }
  831. // reset body axis gyro bias estimates
  832. void NavEKF2::resetGyroBias(void)
  833. {
  834. if (core) {
  835. for (uint8_t i=0; i<num_cores; i++) {
  836. core[i].resetGyroBias();
  837. }
  838. }
  839. }
  840. // Resets the baro so that it reads zero at the current height
  841. // Resets the EKF height to zero
  842. // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
  843. // Returns true if the height datum reset has been performed
  844. // If using a range finder for height no reset is performed and it returns false
  845. bool NavEKF2::resetHeightDatum(void)
  846. {
  847. bool status = true;
  848. if (core) {
  849. for (uint8_t i=0; i<num_cores; i++) {
  850. if (!core[i].resetHeightDatum()) {
  851. status = false;
  852. }
  853. }
  854. } else {
  855. status = false;
  856. }
  857. return status;
  858. }
  859. // Commands the EKF to not use GPS.
  860. // This command must be sent prior to arming as it will only be actioned when the filter is in static mode
  861. // This command is forgotten by the EKF each time it goes back into static mode (eg the vehicle disarms)
  862. // Returns 0 if command rejected
  863. // Returns 1 if attitude, vertical velocity and vertical position will be provided
  864. // Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided
  865. uint8_t NavEKF2::setInhibitGPS(void)
  866. {
  867. if (!core) {
  868. return 0;
  869. }
  870. return core[primary].setInhibitGPS();
  871. }
  872. // return the horizontal speed limit in m/s set by optical flow sensor limits
  873. // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
  874. void NavEKF2::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
  875. {
  876. if (core) {
  877. core[primary].getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
  878. } else {
  879. ekfGndSpdLimit = 400.0f; //return 80% of max filter speed
  880. ekfNavVelGainScaler = 1.0f;
  881. }
  882. }
  883. // return the individual Z-accel bias estimates in m/s^2
  884. void NavEKF2::getAccelZBias(int8_t instance, float &zbias) const
  885. {
  886. if (instance < 0 || instance >= num_cores) instance = primary;
  887. if (core) {
  888. core[instance].getAccelZBias(zbias);
  889. }
  890. }
  891. // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
  892. void NavEKF2::getWind(int8_t instance, Vector3f &wind) const
  893. {
  894. if (instance < 0 || instance >= num_cores) instance = primary;
  895. if (core) {
  896. core[instance].getWind(wind);
  897. }
  898. }
  899. // return earth magnetic field estimates in measurement units / 1000
  900. void NavEKF2::getMagNED(int8_t instance, Vector3f &magNED) const
  901. {
  902. if (instance < 0 || instance >= num_cores) instance = primary;
  903. if (core) {
  904. core[instance].getMagNED(magNED);
  905. }
  906. }
  907. // return body magnetic field estimates in measurement units / 1000
  908. void NavEKF2::getMagXYZ(int8_t instance, Vector3f &magXYZ) const
  909. {
  910. if (instance < 0 || instance >= num_cores) instance = primary;
  911. if (core) {
  912. core[instance].getMagXYZ(magXYZ);
  913. }
  914. }
  915. // return the magnetometer in use for the specified instance
  916. uint8_t NavEKF2::getActiveMag(int8_t instance) const
  917. {
  918. if (instance < 0 || instance >= num_cores) instance = primary;
  919. if (core) {
  920. return core[instance].getActiveMag();
  921. } else {
  922. return 255;
  923. }
  924. }
  925. // Return estimated magnetometer offsets
  926. // Return true if magnetometer offsets are valid
  927. bool NavEKF2::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
  928. {
  929. if (!core) {
  930. return false;
  931. }
  932. // try the primary first, else loop through all of the cores and return when one has offsets for this mag instance
  933. if (core[primary].getMagOffsets(mag_idx, magOffsets)) {
  934. return true;
  935. }
  936. for (uint8_t i=0; i<num_cores; i++) {
  937. if(core[i].getMagOffsets(mag_idx, magOffsets)) {
  938. return true;
  939. }
  940. }
  941. return false;
  942. }
  943. // Return the last calculated latitude, longitude and height in WGS-84
  944. // If a calculated location isn't available, return a raw GPS measurement
  945. // The status will return true if a calculation or raw measurement is available
  946. // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
  947. bool NavEKF2::getLLH(struct Location &loc) const
  948. {
  949. if (!core) {
  950. return false;
  951. }
  952. return core[primary].getLLH(loc);
  953. }
  954. // Return the latitude and longitude and height used to set the NED origin for the specified instance
  955. // An out of range instance (eg -1) returns data for the primary instance
  956. // All NED positions calculated by the filter are relative to this location
  957. // Returns false if the origin has not been set
  958. bool NavEKF2::getOriginLLH(int8_t instance, struct Location &loc) const
  959. {
  960. if (instance < 0 || instance >= num_cores) instance = primary;
  961. if (!core) {
  962. return false;
  963. }
  964. return core[instance].getOriginLLH(loc);
  965. }
  966. // set the latitude and longitude and height used to set the NED origin
  967. // All NED positions calculated by the filter will be relative to this location
  968. // The origin cannot be set if the filter is in a flight mode (eg vehicle armed)
  969. // Returns false if the filter has rejected the attempt to set the origin
  970. bool NavEKF2::setOriginLLH(const Location &loc)
  971. {
  972. if (_fusionModeGPS != 3) {
  973. // we don't allow setting of the EKF origin unless we are
  974. // flying in non-GPS mode. This is to prevent accidental set
  975. // of EKF origin with invalid position or height
  976. gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 refusing set origin");
  977. return false;
  978. }
  979. if (!core) {
  980. return false;
  981. }
  982. bool ret = false;
  983. for (uint8_t i=0; i<num_cores; i++) {
  984. ret |= core[i].setOriginLLH(loc);
  985. }
  986. // return true if any core accepts the new origin
  987. return ret;
  988. }
  989. // return estimated height above ground level
  990. // return false if ground height is not being estimated.
  991. bool NavEKF2::getHAGL(float &HAGL) const
  992. {
  993. if (!core) {
  994. return false;
  995. }
  996. return core[primary].getHAGL(HAGL);
  997. }
  998. // return the Euler roll, pitch and yaw angle in radians for the specified instance
  999. void NavEKF2::getEulerAngles(int8_t instance, Vector3f &eulers) const
  1000. {
  1001. if (instance < 0 || instance >= num_cores) instance = primary;
  1002. if (core) {
  1003. core[instance].getEulerAngles(eulers);
  1004. }
  1005. }
  1006. // return the transformation matrix from XYZ (body) to NED axes
  1007. void NavEKF2::getRotationBodyToNED(Matrix3f &mat) const
  1008. {
  1009. if (core) {
  1010. core[primary].getRotationBodyToNED(mat);
  1011. }
  1012. }
  1013. // return the quaternions defining the rotation from NED to XYZ (body) axes
  1014. void NavEKF2::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const
  1015. {
  1016. if (instance < 0 || instance >= num_cores) instance = primary;
  1017. if (core) {
  1018. Matrix3f mat;
  1019. core[instance].getRotationBodyToNED(mat);
  1020. quat.from_rotation_matrix(mat);
  1021. }
  1022. }
  1023. // return the quaternions defining the rotation from NED to XYZ (autopilot) axes
  1024. void NavEKF2::getQuaternion(int8_t instance, Quaternion &quat) const
  1025. {
  1026. if (instance < 0 || instance >= num_cores) instance = primary;
  1027. if (core) {
  1028. core[instance].getQuaternion(quat);
  1029. }
  1030. }
  1031. // return the innovations for the specified instance
  1032. void NavEKF2::getInnovations(int8_t instance, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
  1033. {
  1034. if (instance < 0 || instance >= num_cores) instance = primary;
  1035. if (core) {
  1036. core[instance].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
  1037. }
  1038. }
  1039. // publish output observer angular, velocity and position tracking error
  1040. void NavEKF2::getOutputTrackingError(int8_t instance, Vector3f &error) const
  1041. {
  1042. if (instance < 0 || instance >= num_cores) instance = primary;
  1043. if (core) {
  1044. core[instance].getOutputTrackingError(error);
  1045. }
  1046. }
  1047. // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements
  1048. void NavEKF2::getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
  1049. {
  1050. if (instance < 0 || instance >= num_cores) instance = primary;
  1051. if (core) {
  1052. core[instance].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
  1053. }
  1054. }
  1055. // should we use the compass? This is public so it can be used for
  1056. // reporting via ahrs.use_compass()
  1057. bool NavEKF2::use_compass(void) const
  1058. {
  1059. if (!core) {
  1060. return false;
  1061. }
  1062. return core[primary].use_compass();
  1063. }
  1064. // write the raw optical flow measurements
  1065. // rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality
  1066. // rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes.
  1067. // rawGyroRates are the sensor rotation rates in rad/sec measured by the sensors internal gyro
  1068. // The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
  1069. // msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
  1070. // posOffset is the XYZ flow sensor position in the body frame in m
  1071. void NavEKF2::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
  1072. {
  1073. if (core) {
  1074. for (uint8_t i=0; i<num_cores; i++) {
  1075. core[i].writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
  1076. }
  1077. }
  1078. }
  1079. // return data for debugging optical flow fusion
  1080. void NavEKF2::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov,
  1081. float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
  1082. {
  1083. if (instance < 0 || instance >= num_cores) instance = primary;
  1084. if (core) {
  1085. core[instance].getFlowDebug(varFlow, gndOffset, flowInnovX, flowInnovY, auxInnov, HAGL, rngInnov, range, gndOffsetErr);
  1086. }
  1087. }
  1088. // return data for debugging range beacon fusion
  1089. bool NavEKF2::getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow) const
  1090. {
  1091. if (instance < 0 || instance >= num_cores) instance = primary;
  1092. if (core) {
  1093. return core[instance].getRangeBeaconDebug(ID, rng, innov, innovVar, testRatio, beaconPosNED, offsetHigh, offsetLow);
  1094. } else {
  1095. return false;
  1096. }
  1097. }
  1098. // called by vehicle code to specify that a takeoff is happening
  1099. // causes the EKF to compensate for expected barometer errors due to ground effect
  1100. void NavEKF2::setTakeoffExpected(bool val)
  1101. {
  1102. if (core) {
  1103. for (uint8_t i=0; i<num_cores; i++) {
  1104. core[i].setTakeoffExpected(val);
  1105. }
  1106. }
  1107. }
  1108. // called by vehicle code to specify that a touchdown is expected to happen
  1109. // causes the EKF to compensate for expected barometer errors due to ground effect
  1110. void NavEKF2::setTouchdownExpected(bool val)
  1111. {
  1112. if (core) {
  1113. for (uint8_t i=0; i<num_cores; i++) {
  1114. core[i].setTouchdownExpected(val);
  1115. }
  1116. }
  1117. }
  1118. // Set to true if the terrain underneath is stable enough to be used as a height reference
  1119. // in combination with a range finder. Set to false if the terrain underneath the vehicle
  1120. // cannot be used as a height reference
  1121. void NavEKF2::setTerrainHgtStable(bool val)
  1122. {
  1123. if (core) {
  1124. for (uint8_t i=0; i<num_cores; i++) {
  1125. core[i].setTerrainHgtStable(val);
  1126. }
  1127. }
  1128. }
  1129. /*
  1130. return the filter fault status as a bitmasked integer
  1131. 0 = quaternions are NaN
  1132. 1 = velocities are NaN
  1133. 2 = badly conditioned X magnetometer fusion
  1134. 3 = badly conditioned Y magnetometer fusion
  1135. 5 = badly conditioned Z magnetometer fusion
  1136. 6 = badly conditioned airspeed fusion
  1137. 7 = badly conditioned synthetic sideslip fusion
  1138. 7 = filter is not initialised
  1139. */
  1140. void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const
  1141. {
  1142. if (instance < 0 || instance >= num_cores) instance = primary;
  1143. if (core) {
  1144. core[instance].getFilterFaults(faults);
  1145. } else {
  1146. faults = 0;
  1147. }
  1148. }
  1149. /*
  1150. return filter timeout status as a bitmasked integer
  1151. 0 = position measurement timeout
  1152. 1 = velocity measurement timeout
  1153. 2 = height measurement timeout
  1154. 3 = magnetometer measurement timeout
  1155. 5 = unassigned
  1156. 6 = unassigned
  1157. 7 = unassigned
  1158. 7 = unassigned
  1159. */
  1160. void NavEKF2::getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
  1161. {
  1162. if (instance < 0 || instance >= num_cores) instance = primary;
  1163. if (core) {
  1164. core[instance].getFilterTimeouts(timeouts);
  1165. } else {
  1166. timeouts = 0;
  1167. }
  1168. }
  1169. /*
  1170. return filter status flags
  1171. */
  1172. void NavEKF2::getFilterStatus(int8_t instance, nav_filter_status &status) const
  1173. {
  1174. if (instance < 0 || instance >= num_cores) instance = primary;
  1175. if (core) {
  1176. core[instance].getFilterStatus(status);
  1177. } else {
  1178. memset(&status, 0, sizeof(status));
  1179. }
  1180. }
  1181. /*
  1182. return filter gps quality check status
  1183. */
  1184. void NavEKF2::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const
  1185. {
  1186. if (instance < 0 || instance >= num_cores) instance = primary;
  1187. if (core) {
  1188. core[instance].getFilterGpsStatus(status);
  1189. } else {
  1190. memset(&status, 0, sizeof(status));
  1191. }
  1192. }
  1193. // send an EKF_STATUS_REPORT message to GCS
  1194. void NavEKF2::send_status_report(mavlink_channel_t chan)
  1195. {
  1196. if (core) {
  1197. core[primary].send_status_report(chan);
  1198. }
  1199. }
  1200. // provides the height limit to be observed by the control loops
  1201. // returns false if no height limiting is required
  1202. // this is needed to ensure the vehicle does not fly too high when using optical flow navigation
  1203. bool NavEKF2::getHeightControlLimit(float &height) const
  1204. {
  1205. if (!core) {
  1206. return false;
  1207. }
  1208. return core[primary].getHeightControlLimit(height);
  1209. }
  1210. // Returns the amount of yaw angle change (in radians) due to the last yaw angle reset or core selection switch
  1211. // Returns the time of the last yaw angle reset or 0 if no reset or core switch has ever occurred
  1212. // Where there are multiple consumers, they must access this function on the same frame as each other
  1213. uint32_t NavEKF2::getLastYawResetAngle(float &yawAngDelta)
  1214. {
  1215. if (!core) {
  1216. return 0;
  1217. }
  1218. yawAngDelta = 0.0f;
  1219. // Do the conversion to msec in one place
  1220. uint32_t now_time_ms = imuSampleTime_us / 1000;
  1221. // The last time we switched to the current primary core is the first reset event
  1222. uint32_t lastYawReset_ms = yaw_reset_data.last_primary_change;
  1223. // There has been a change notification in the primary core that the controller has not consumed
  1224. // or this is a repeated acce
  1225. if (yaw_reset_data.core_changed || yaw_reset_data.last_function_call == now_time_ms) {
  1226. yawAngDelta = yaw_reset_data.core_delta;
  1227. yaw_reset_data.core_changed = false;
  1228. }
  1229. // Record last time controller got the yaw reset
  1230. yaw_reset_data.last_function_call = now_time_ms;
  1231. // There has been a reset inside the core since we switched so update the time and delta
  1232. float temp_yawAng;
  1233. uint32_t lastCoreYawReset_ms = core[primary].getLastYawResetAngle(temp_yawAng);
  1234. if (lastCoreYawReset_ms > lastYawReset_ms) {
  1235. yawAngDelta = wrap_PI(yawAngDelta + temp_yawAng);
  1236. lastYawReset_ms = lastCoreYawReset_ms;
  1237. }
  1238. return lastYawReset_ms;
  1239. }
  1240. // Returns the amount of NE position change due to the last position reset or core switch in metres
  1241. // Returns the time of the last reset or 0 if no reset or core switch has ever occurred
  1242. // Where there are multiple consumers, they must access this function on the same frame as each other
  1243. uint32_t NavEKF2::getLastPosNorthEastReset(Vector2f &posDelta)
  1244. {
  1245. if (!core) {
  1246. return 0;
  1247. }
  1248. posDelta.zero();
  1249. // Do the conversion to msec in one place
  1250. uint32_t now_time_ms = imuSampleTime_us / 1000;
  1251. // The last time we switched to the current primary core is the first reset event
  1252. uint32_t lastPosReset_ms = pos_reset_data.last_primary_change;
  1253. // There has been a change in the primary core that the controller has not consumed
  1254. // allow for multiple consumers on the same frame
  1255. if (pos_reset_data.core_changed || pos_reset_data.last_function_call == now_time_ms) {
  1256. posDelta = pos_reset_data.core_delta;
  1257. pos_reset_data.core_changed = false;
  1258. }
  1259. // Record last time controller got the position reset
  1260. pos_reset_data.last_function_call = now_time_ms;
  1261. // There has been a reset inside the core since we switched so update the time and delta
  1262. Vector2f tempPosDelta;
  1263. uint32_t lastCorePosReset_ms = core[primary].getLastPosNorthEastReset(tempPosDelta);
  1264. if (lastCorePosReset_ms > lastPosReset_ms) {
  1265. posDelta = posDelta + tempPosDelta;
  1266. lastPosReset_ms = lastCorePosReset_ms;
  1267. }
  1268. return lastPosReset_ms;
  1269. }
  1270. // return the amount of NE velocity change due to the last velocity reset in metres/sec
  1271. // returns the time of the last reset or 0 if no reset has ever occurred
  1272. uint32_t NavEKF2::getLastVelNorthEastReset(Vector2f &vel) const
  1273. {
  1274. if (!core) {
  1275. return 0;
  1276. }
  1277. return core[primary].getLastVelNorthEastReset(vel);
  1278. }
  1279. // report the reason for why the backend is refusing to initialise
  1280. const char *NavEKF2::prearm_failure_reason(void) const
  1281. {
  1282. if (!core) {
  1283. return nullptr;
  1284. }
  1285. for (uint8_t i = 0; i < num_cores; i++) {
  1286. const char * failure = core[i].prearm_failure_reason();
  1287. if (failure != nullptr) {
  1288. return failure;
  1289. }
  1290. }
  1291. return nullptr;
  1292. }
  1293. // Returns the amount of vertical position change due to the last reset or core switch in metres
  1294. // Returns the time of the last reset or 0 if no reset or core switch has ever occurred
  1295. // Where there are multiple consumers, they must access this function on the same frame as each other
  1296. uint32_t NavEKF2::getLastPosDownReset(float &posDelta)
  1297. {
  1298. if (!core) {
  1299. return 0;
  1300. }
  1301. posDelta = 0.0f;
  1302. // Do the conversion to msec in one place
  1303. uint32_t now_time_ms = imuSampleTime_us / 1000;
  1304. // The last time we switched to the current primary core is the first reset event
  1305. uint32_t lastPosReset_ms = pos_down_reset_data.last_primary_change;
  1306. // There has been a change in the primary core that the controller has not consumed
  1307. // allow for multiple consumers on the same frame
  1308. if (pos_down_reset_data.core_changed || pos_down_reset_data.last_function_call == now_time_ms) {
  1309. posDelta = pos_down_reset_data.core_delta;
  1310. pos_down_reset_data.core_changed = false;
  1311. }
  1312. // Record last time controller got the position reset
  1313. pos_down_reset_data.last_function_call = now_time_ms;
  1314. // There has been a reset inside the core since we switched so update the time and delta
  1315. float tempPosDelta;
  1316. uint32_t lastCorePosReset_ms = core[primary].getLastPosDownReset(tempPosDelta);
  1317. if (lastCorePosReset_ms > lastPosReset_ms) {
  1318. posDelta += tempPosDelta;
  1319. lastPosReset_ms = lastCorePosReset_ms;
  1320. }
  1321. return lastPosReset_ms;
  1322. }
  1323. // update the yaw reset data to capture changes due to a lane switch
  1324. void NavEKF2::updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
  1325. {
  1326. Vector3f eulers_old_primary, eulers_new_primary;
  1327. float old_yaw_delta;
  1328. // If core yaw reset data has been consumed reset delta to zero
  1329. if (!yaw_reset_data.core_changed) {
  1330. yaw_reset_data.core_delta = 0;
  1331. }
  1332. // If current primary has reset yaw after controller got it, add it to the delta
  1333. if (core[old_primary].getLastYawResetAngle(old_yaw_delta) > yaw_reset_data.last_function_call) {
  1334. yaw_reset_data.core_delta += old_yaw_delta;
  1335. }
  1336. // Record the yaw delta between current core and new primary core and the timestamp of the core change
  1337. // Add current delta in case it hasn't been consumed yet
  1338. core[old_primary].getEulerAngles(eulers_old_primary);
  1339. core[new_primary].getEulerAngles(eulers_new_primary);
  1340. yaw_reset_data.core_delta = wrap_PI(eulers_new_primary.z - eulers_old_primary.z + yaw_reset_data.core_delta);
  1341. yaw_reset_data.last_primary_change = imuSampleTime_us / 1000;
  1342. yaw_reset_data.core_changed = true;
  1343. }
  1344. // update the position reset data to capture changes due to a lane switch
  1345. void NavEKF2::updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
  1346. {
  1347. Vector2f pos_old_primary, pos_new_primary, old_pos_delta;
  1348. // If core position reset data has been consumed reset delta to zero
  1349. if (!pos_reset_data.core_changed) {
  1350. pos_reset_data.core_delta.zero();
  1351. }
  1352. // If current primary has reset position after controller got it, add it to the delta
  1353. if (core[old_primary].getLastPosNorthEastReset(old_pos_delta) > pos_reset_data.last_function_call) {
  1354. pos_reset_data.core_delta += old_pos_delta;
  1355. }
  1356. // Record the position delta between current core and new primary core and the timestamp of the core change
  1357. // Add current delta in case it hasn't been consumed yet
  1358. core[old_primary].getPosNE(pos_old_primary);
  1359. core[new_primary].getPosNE(pos_new_primary);
  1360. pos_reset_data.core_delta = pos_new_primary - pos_old_primary + pos_reset_data.core_delta;
  1361. pos_reset_data.last_primary_change = imuSampleTime_us / 1000;
  1362. pos_reset_data.core_changed = true;
  1363. }
  1364. // Update the vertical position reset data to capture changes due to a core switch
  1365. // This should be called after the decision to switch cores has been made, but before the
  1366. // new primary EKF update has been run
  1367. void NavEKF2::updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
  1368. {
  1369. float posDownOldPrimary, posDownNewPrimary, oldPosDownDelta;
  1370. // If core position reset data has been consumed reset delta to zero
  1371. if (!pos_down_reset_data.core_changed) {
  1372. pos_down_reset_data.core_delta = 0.0f;
  1373. }
  1374. // If current primary has reset position after controller got it, add it to the delta
  1375. if (core[old_primary].getLastPosDownReset(oldPosDownDelta) > pos_down_reset_data.last_function_call) {
  1376. pos_down_reset_data.core_delta += oldPosDownDelta;
  1377. }
  1378. // Record the position delta between current core and new primary core and the timestamp of the core change
  1379. // Add current delta in case it hasn't been consumed yet
  1380. core[old_primary].getPosD(posDownOldPrimary);
  1381. core[new_primary].getPosD(posDownNewPrimary);
  1382. pos_down_reset_data.core_delta = posDownNewPrimary - posDownOldPrimary + pos_down_reset_data.core_delta;
  1383. pos_down_reset_data.last_primary_change = imuSampleTime_us / 1000;
  1384. pos_down_reset_data.core_changed = true;
  1385. }
  1386. /*
  1387. get timing statistics structure
  1388. */
  1389. void NavEKF2::getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
  1390. {
  1391. if (instance < 0 || instance >= num_cores) {
  1392. instance = primary;
  1393. }
  1394. if (core) {
  1395. core[instance].getTimingStatistics(timing);
  1396. } else {
  1397. memset(&timing, 0, sizeof(timing));
  1398. }
  1399. }
  1400. /*
  1401. * Write position and quaternion data from an external navigation system
  1402. *
  1403. * pos : XYZ position (m) in a RH navigation frame with the Z axis pointing down and XY axes horizontal. Frame must be aligned with NED if the magnetomer is being used for yaw.
  1404. * quat : quaternion describing the rotation from navigation frame to body frame
  1405. * posErr : 1-sigma spherical position error (m)
  1406. * angErr : 1-sigma spherical angle error (rad)
  1407. * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec)
  1408. * resetTime_ms : system time of the last position reset request (mSec)
  1409. *
  1410. */
  1411. void NavEKF2::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
  1412. {
  1413. if (core) {
  1414. for (uint8_t i=0; i<num_cores; i++) {
  1415. core[i].writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
  1416. }
  1417. }
  1418. }
  1419. // check if external navigation is being used for yaw observation
  1420. bool NavEKF2::isExtNavUsedForYaw() const
  1421. {
  1422. if (core) {
  1423. return core[primary].isExtNavUsedForYaw();
  1424. }
  1425. return false;
  1426. }