AP_NavEKF3.cpp 69 KB

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