AP_AHRS_NavEKF.cpp 51 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * NavEKF based AHRS (Attitude Heading Reference System) interface for
  15. * ArduPilot
  16. *
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include "AP_AHRS.h"
  20. #include "AP_AHRS_View.h"
  21. #include <AP_Vehicle/AP_Vehicle.h>
  22. #include <GCS_MAVLink/GCS.h>
  23. #include <AP_Module/AP_Module.h>
  24. #include <AP_GPS/AP_GPS.h>
  25. #include <AP_Baro/AP_Baro.h>
  26. #if AP_AHRS_NAVEKF_AVAILABLE
  27. #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10)
  28. #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20)
  29. extern const AP_HAL::HAL& hal;
  30. // constructor
  31. AP_AHRS_NavEKF::AP_AHRS_NavEKF(NavEKF2 &_EKF2,
  32. NavEKF3 &_EKF3,
  33. Flags flags) :
  34. AP_AHRS_DCM(),
  35. EKF2(_EKF2),
  36. EKF3(_EKF3),
  37. _ekf_flags(flags)
  38. {
  39. _dcm_matrix.identity();
  40. }
  41. // return the smoothed gyro vector corrected for drift
  42. const Vector3f &AP_AHRS_NavEKF::get_gyro(void) const
  43. {
  44. if (!active_EKF_type()) {
  45. return AP_AHRS_DCM::get_gyro();
  46. }
  47. return _gyro_estimate;
  48. }
  49. const Matrix3f &AP_AHRS_NavEKF::get_rotation_body_to_ned(void) const
  50. {
  51. if (!active_EKF_type()) {
  52. return AP_AHRS_DCM::get_rotation_body_to_ned();
  53. }
  54. return _dcm_matrix;
  55. }
  56. const Vector3f &AP_AHRS_NavEKF::get_gyro_drift(void) const
  57. {
  58. if (!active_EKF_type()) {
  59. return AP_AHRS_DCM::get_gyro_drift();
  60. }
  61. return _gyro_drift;
  62. }
  63. // reset the current gyro drift estimate
  64. // should be called if gyro offsets are recalculated
  65. void AP_AHRS_NavEKF::reset_gyro_drift(void)
  66. {
  67. // support locked access functions to AHRS data
  68. WITH_SEMAPHORE(_rsem);
  69. // update DCM
  70. AP_AHRS_DCM::reset_gyro_drift();
  71. // reset the EKF gyro bias states
  72. EKF2.resetGyroBias();
  73. EKF3.resetGyroBias();
  74. }
  75. void AP_AHRS_NavEKF::update(bool skip_ins_update)
  76. {
  77. // support locked access functions to AHRS data
  78. WITH_SEMAPHORE(_rsem);
  79. // drop back to normal priority if we were boosted by the INS
  80. // calling delay_microseconds_boost()
  81. hal.scheduler->boost_end();
  82. // EKF1 is no longer supported - handle case where it is selected
  83. if (_ekf_type == 1) {
  84. _ekf_type.set(2);
  85. }
  86. update_DCM(skip_ins_update);
  87. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  88. update_SITL();
  89. #endif
  90. if (_ekf_type == 2) {
  91. // if EK2 is primary then run EKF2 first to give it CPU
  92. // priority
  93. update_EKF2();
  94. update_EKF3();
  95. } else {
  96. // otherwise run EKF3 first
  97. update_EKF3();
  98. update_EKF2();
  99. }
  100. #if AP_MODULE_SUPPORTED
  101. // call AHRS_update hook if any
  102. AP_Module::call_hook_AHRS_update(*this);
  103. #endif
  104. // push gyros if optical flow present
  105. if (hal.opticalflow) {
  106. const Vector3f &exported_gyro_bias = get_gyro_drift();
  107. hal.opticalflow->push_gyro_bias(exported_gyro_bias.x, exported_gyro_bias.y);
  108. }
  109. if (_view != nullptr) {
  110. // update optional alternative attitude view
  111. _view->update(skip_ins_update);
  112. }
  113. #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
  114. // update NMEA output
  115. update_nmea_out();
  116. #endif
  117. }
  118. void AP_AHRS_NavEKF::update_DCM(bool skip_ins_update)
  119. {
  120. // we need to restore the old DCM attitude values as these are
  121. // used internally in DCM to calculate error values for gyro drift
  122. // correction
  123. roll = _dcm_attitude.x;
  124. pitch = _dcm_attitude.y;
  125. yaw = _dcm_attitude.z;
  126. update_cd_values();
  127. AP_AHRS_DCM::update(skip_ins_update);
  128. // keep DCM attitude available for get_secondary_attitude()
  129. _dcm_attitude(roll, pitch, yaw);
  130. }
  131. void AP_AHRS_NavEKF::update_EKF2(void)
  132. {
  133. if (!_ekf2_started) {
  134. // wait 1 second for DCM to output a valid tilt error estimate
  135. if (start_time_ms == 0) {
  136. start_time_ms = AP_HAL::millis();
  137. }
  138. if (AP_HAL::millis() - start_time_ms > startup_delay_ms || _force_ekf) {
  139. _ekf2_started = EKF2.InitialiseFilter();
  140. if (_force_ekf) {
  141. return;
  142. }
  143. }
  144. }
  145. if (_ekf2_started) {
  146. EKF2.UpdateFilter();
  147. if (active_EKF_type() == EKF_TYPE2) {
  148. Vector3f eulers;
  149. EKF2.getRotationBodyToNED(_dcm_matrix);
  150. EKF2.getEulerAngles(-1,eulers);
  151. roll = eulers.x;
  152. pitch = eulers.y;
  153. yaw = eulers.z;
  154. update_cd_values();
  155. update_trig();
  156. // Use the primary EKF to select the primary gyro
  157. const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex();
  158. const AP_InertialSensor &_ins = AP::ins();
  159. // get gyro bias for primary EKF and change sign to give gyro drift
  160. // Note sign convention used by EKF is bias = measurement - truth
  161. _gyro_drift.zero();
  162. EKF2.getGyroBias(-1,_gyro_drift);
  163. _gyro_drift = -_gyro_drift;
  164. // calculate corrected gyro estimate for get_gyro()
  165. _gyro_estimate.zero();
  166. if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
  167. // the primary IMU is undefined so use an uncorrected default value from the INS library
  168. _gyro_estimate = _ins.get_gyro();
  169. } else {
  170. // use the same IMU as the primary EKF and correct for gyro drift
  171. _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift;
  172. }
  173. // get z accel bias estimate from active EKF (this is usually for the primary IMU)
  174. float abias = 0;
  175. EKF2.getAccelZBias(-1,abias);
  176. // This EKF is currently using primary_imu, and abias applies to only that IMU
  177. for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
  178. Vector3f accel = _ins.get_accel(i);
  179. if (i == primary_imu) {
  180. accel.z -= abias;
  181. }
  182. if (_ins.get_accel_health(i)) {
  183. _accel_ef_ekf[i] = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
  184. }
  185. }
  186. _accel_ef_ekf_blended = _accel_ef_ekf[primary_imu>=0?primary_imu:_ins.get_primary_accel()];
  187. nav_filter_status filt_state;
  188. EKF2.getFilterStatus(-1,filt_state);
  189. AP_Notify::flags.gps_fusion = filt_state.flags.using_gps; // Drives AP_Notify flag for usable GPS.
  190. AP_Notify::flags.gps_glitching = filt_state.flags.gps_glitching;
  191. AP_Notify::flags.have_pos_abs = filt_state.flags.horiz_pos_abs;
  192. }
  193. }
  194. }
  195. void AP_AHRS_NavEKF::update_EKF3(void)
  196. {
  197. if (!_ekf3_started) {
  198. // wait 1 second for DCM to output a valid tilt error estimate
  199. if (start_time_ms == 0) {
  200. start_time_ms = AP_HAL::millis();
  201. }
  202. if (AP_HAL::millis() - start_time_ms > startup_delay_ms || _force_ekf) {
  203. _ekf3_started = EKF3.InitialiseFilter();
  204. if (_force_ekf) {
  205. return;
  206. }
  207. }
  208. }
  209. if (_ekf3_started) {
  210. EKF3.UpdateFilter();
  211. if (active_EKF_type() == EKF_TYPE3) {
  212. Vector3f eulers;
  213. EKF3.getRotationBodyToNED(_dcm_matrix);
  214. EKF3.getEulerAngles(-1,eulers);
  215. roll = eulers.x;
  216. pitch = eulers.y;
  217. yaw = eulers.z;
  218. update_cd_values();
  219. update_trig();
  220. const AP_InertialSensor &_ins = AP::ins();
  221. // Use the primary EKF to select the primary gyro
  222. const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex();
  223. // get gyro bias for primary EKF and change sign to give gyro drift
  224. // Note sign convention used by EKF is bias = measurement - truth
  225. _gyro_drift.zero();
  226. EKF3.getGyroBias(-1,_gyro_drift);
  227. _gyro_drift = -_gyro_drift;
  228. // calculate corrected gyro estimate for get_gyro()
  229. _gyro_estimate.zero();
  230. if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) {
  231. // the primary IMU is undefined so use an uncorrected default value from the INS library
  232. _gyro_estimate = _ins.get_gyro();
  233. } else {
  234. // use the same IMU as the primary EKF and correct for gyro drift
  235. _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift;
  236. }
  237. // get 3-axis accel bias festimates for active EKF (this is usually for the primary IMU)
  238. Vector3f abias;
  239. EKF3.getAccelBias(-1,abias);
  240. // This EKF uses the primary IMU
  241. // Eventually we will run a separate instance of the EKF for each IMU and do the selection and blending of EKF outputs upstream
  242. // update _accel_ef_ekf
  243. for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
  244. Vector3f accel = _ins.get_accel(i);
  245. if (i==_ins.get_primary_accel()) {
  246. accel -= abias;
  247. }
  248. if (_ins.get_accel_health(i)) {
  249. _accel_ef_ekf[i] = _dcm_matrix * accel;
  250. }
  251. }
  252. _accel_ef_ekf_blended = _accel_ef_ekf[_ins.get_primary_accel()];
  253. nav_filter_status filt_state;
  254. EKF3.getFilterStatus(-1,filt_state);
  255. AP_Notify::flags.gps_fusion = filt_state.flags.using_gps; // Drives AP_Notify flag for usable GPS.
  256. AP_Notify::flags.gps_glitching = filt_state.flags.gps_glitching;
  257. AP_Notify::flags.have_pos_abs = filt_state.flags.horiz_pos_abs;
  258. }
  259. }
  260. }
  261. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  262. void AP_AHRS_NavEKF::update_SITL(void)
  263. {
  264. if (_sitl == nullptr) {
  265. _sitl = AP::sitl();
  266. if (_sitl == nullptr) {
  267. return;
  268. }
  269. }
  270. const struct SITL::sitl_fdm &fdm = _sitl->state;
  271. const AP_InertialSensor &_ins = AP::ins();
  272. if (active_EKF_type() == EKF_TYPE_SITL) {
  273. fdm.quaternion.rotation_matrix(_dcm_matrix);
  274. _dcm_matrix = _dcm_matrix * get_rotation_vehicle_body_to_autopilot_body();
  275. _dcm_matrix.to_euler(&roll, &pitch, &yaw);
  276. update_cd_values();
  277. update_trig();
  278. _gyro_drift.zero();
  279. _gyro_estimate = _ins.get_gyro();
  280. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  281. const Vector3f &accel = _ins.get_accel(i);
  282. _accel_ef_ekf[i] = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
  283. }
  284. _accel_ef_ekf_blended = _accel_ef_ekf[0];
  285. }
  286. if (_sitl->odom_enable) {
  287. // use SITL states to write body frame odometry data at 20Hz
  288. uint32_t timeStamp_ms = AP_HAL::millis();
  289. if (timeStamp_ms - _last_body_odm_update_ms > 50) {
  290. const float quality = 100.0f;
  291. const Vector3f posOffset(0.0f, 0.0f, 0.0f);
  292. const float delTime = 0.001f * (timeStamp_ms - _last_body_odm_update_ms);
  293. _last_body_odm_update_ms = timeStamp_ms;
  294. timeStamp_ms -= (timeStamp_ms - _last_body_odm_update_ms)/2; // correct for first order hold average delay
  295. Vector3f delAng = _ins.get_gyro();
  296. delAng *= delTime;
  297. // rotate earth velocity into body frame and calculate delta position
  298. Matrix3f Tbn;
  299. Tbn.from_euler(radians(fdm.rollDeg),radians(fdm.pitchDeg),radians(fdm.yawDeg));
  300. const Vector3f earth_vel(fdm.speedN,fdm.speedE,fdm.speedD);
  301. const Vector3f delPos = Tbn.transposed() * (earth_vel * delTime);
  302. // write to EKF
  303. EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
  304. }
  305. }
  306. }
  307. #endif // CONFIG_HAL_BOARD
  308. // accelerometer values in the earth frame in m/s/s
  309. const Vector3f &AP_AHRS_NavEKF::get_accel_ef(uint8_t i) const
  310. {
  311. if (active_EKF_type() == EKF_TYPE_NONE) {
  312. return AP_AHRS_DCM::get_accel_ef(i);
  313. }
  314. return _accel_ef_ekf[i];
  315. }
  316. // blended accelerometer values in the earth frame in m/s/s
  317. const Vector3f &AP_AHRS_NavEKF::get_accel_ef_blended(void) const
  318. {
  319. if (active_EKF_type() == EKF_TYPE_NONE) {
  320. return AP_AHRS_DCM::get_accel_ef_blended();
  321. }
  322. return _accel_ef_ekf_blended;
  323. }
  324. void AP_AHRS_NavEKF::reset(bool recover_eulers)
  325. {
  326. // support locked access functions to AHRS data
  327. WITH_SEMAPHORE(_rsem);
  328. AP_AHRS_DCM::reset(recover_eulers);
  329. _dcm_attitude(roll, pitch, yaw);
  330. if (_ekf2_started) {
  331. _ekf2_started = EKF2.InitialiseFilter();
  332. }
  333. if (_ekf3_started) {
  334. _ekf3_started = EKF3.InitialiseFilter();
  335. }
  336. }
  337. // reset the current attitude, used on new IMU calibration
  338. void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
  339. {
  340. // support locked access functions to AHRS data
  341. WITH_SEMAPHORE(_rsem);
  342. AP_AHRS_DCM::reset_attitude(_roll, _pitch, _yaw);
  343. _dcm_attitude(roll, pitch, yaw);
  344. if (_ekf2_started) {
  345. _ekf2_started = EKF2.InitialiseFilter();
  346. }
  347. if (_ekf3_started) {
  348. _ekf3_started = EKF3.InitialiseFilter();
  349. }
  350. }
  351. // dead-reckoning support
  352. bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
  353. {
  354. switch (active_EKF_type()) {
  355. case EKF_TYPE_NONE:
  356. return AP_AHRS_DCM::get_position(loc);
  357. case EKF_TYPE2:
  358. if (EKF2.getLLH(loc)) {
  359. return true;
  360. }
  361. break;
  362. case EKF_TYPE3:
  363. if (EKF3.getLLH(loc)) {
  364. return true;
  365. }
  366. break;
  367. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  368. case EKF_TYPE_SITL: {
  369. if (_sitl) {
  370. const struct SITL::sitl_fdm &fdm = _sitl->state;
  371. loc = {};
  372. loc.lat = fdm.latitude * 1e7;
  373. loc.lng = fdm.longitude * 1e7;
  374. loc.alt = fdm.altitude*100;
  375. return true;
  376. }
  377. break;
  378. }
  379. #endif
  380. default:
  381. break;
  382. }
  383. return AP_AHRS_DCM::get_position(loc);
  384. }
  385. // status reporting of estimated errors
  386. float AP_AHRS_NavEKF::get_error_rp(void) const
  387. {
  388. return AP_AHRS_DCM::get_error_rp();
  389. }
  390. float AP_AHRS_NavEKF::get_error_yaw(void) const
  391. {
  392. return AP_AHRS_DCM::get_error_yaw();
  393. }
  394. // return a wind estimation vector, in m/s
  395. Vector3f AP_AHRS_NavEKF::wind_estimate(void) const
  396. {
  397. Vector3f wind;
  398. switch (active_EKF_type()) {
  399. case EKF_TYPE_NONE:
  400. wind = AP_AHRS_DCM::wind_estimate();
  401. break;
  402. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  403. case EKF_TYPE_SITL:
  404. wind.zero();
  405. break;
  406. #endif
  407. case EKF_TYPE2:
  408. EKF2.getWind(-1,wind);
  409. break;
  410. case EKF_TYPE3:
  411. EKF3.getWind(-1,wind);
  412. break;
  413. }
  414. return wind;
  415. }
  416. // return an airspeed estimate if available. return true
  417. // if we have an estimate
  418. bool AP_AHRS_NavEKF::airspeed_estimate(float *airspeed_ret) const
  419. {
  420. return AP_AHRS_DCM::airspeed_estimate(airspeed_ret);
  421. }
  422. // true if compass is being used
  423. bool AP_AHRS_NavEKF::use_compass(void)
  424. {
  425. switch (active_EKF_type()) {
  426. case EKF_TYPE_NONE:
  427. break;
  428. case EKF_TYPE2:
  429. return EKF2.use_compass();
  430. case EKF_TYPE3:
  431. return EKF3.use_compass();
  432. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  433. case EKF_TYPE_SITL:
  434. return true;
  435. #endif
  436. }
  437. return AP_AHRS_DCM::use_compass();
  438. }
  439. // return secondary attitude solution if available, as eulers in radians
  440. bool AP_AHRS_NavEKF::get_secondary_attitude(Vector3f &eulers) const
  441. {
  442. switch (active_EKF_type()) {
  443. case EKF_TYPE_NONE:
  444. // EKF is secondary
  445. EKF2.getEulerAngles(-1, eulers);
  446. return _ekf2_started;
  447. case EKF_TYPE2:
  448. case EKF_TYPE3:
  449. default:
  450. // DCM is secondary
  451. eulers = _dcm_attitude;
  452. return true;
  453. }
  454. }
  455. // return secondary attitude solution if available, as quaternion
  456. bool AP_AHRS_NavEKF::get_secondary_quaternion(Quaternion &quat) const
  457. {
  458. switch (active_EKF_type()) {
  459. case EKF_TYPE_NONE:
  460. // EKF is secondary
  461. EKF2.getQuaternion(-1, quat);
  462. return _ekf2_started;
  463. case EKF_TYPE2:
  464. case EKF_TYPE3:
  465. default:
  466. // DCM is secondary
  467. quat.from_rotation_matrix(AP_AHRS_DCM::get_rotation_body_to_ned());
  468. return true;
  469. }
  470. }
  471. // return secondary position solution if available
  472. bool AP_AHRS_NavEKF::get_secondary_position(struct Location &loc) const
  473. {
  474. switch (active_EKF_type()) {
  475. case EKF_TYPE_NONE:
  476. // EKF is secondary
  477. EKF2.getLLH(loc);
  478. return _ekf2_started;
  479. case EKF_TYPE2:
  480. case EKF_TYPE3:
  481. default:
  482. // return DCM position
  483. AP_AHRS_DCM::get_position(loc);
  484. return true;
  485. }
  486. }
  487. // EKF has a better ground speed vector estimate
  488. Vector2f AP_AHRS_NavEKF::groundspeed_vector(void)
  489. {
  490. Vector3f vec;
  491. switch (active_EKF_type()) {
  492. case EKF_TYPE_NONE:
  493. return AP_AHRS_DCM::groundspeed_vector();
  494. case EKF_TYPE2:
  495. default:
  496. EKF2.getVelNED(-1,vec);
  497. return Vector2f(vec.x, vec.y);
  498. case EKF_TYPE3:
  499. EKF3.getVelNED(-1,vec);
  500. return Vector2f(vec.x, vec.y);
  501. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  502. case EKF_TYPE_SITL: {
  503. if (_sitl) {
  504. const struct SITL::sitl_fdm &fdm = _sitl->state;
  505. return Vector2f(fdm.speedN, fdm.speedE);
  506. } else {
  507. return AP_AHRS_DCM::groundspeed_vector();
  508. }
  509. }
  510. #endif
  511. }
  512. }
  513. // set the EKF's origin location in 10e7 degrees. This should only
  514. // be called when the EKF has no absolute position reference (i.e. GPS)
  515. // from which to decide the origin on its own
  516. bool AP_AHRS_NavEKF::set_origin(const Location &loc)
  517. {
  518. const bool ret2 = EKF2.setOriginLLH(loc);
  519. const bool ret3 = EKF3.setOriginLLH(loc);
  520. // return success if active EKF's origin was set
  521. switch (active_EKF_type()) {
  522. case EKF_TYPE2:
  523. return ret2;
  524. case EKF_TYPE3:
  525. return ret3;
  526. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  527. case EKF_TYPE_SITL:
  528. if (_sitl) {
  529. struct SITL::sitl_fdm &fdm = _sitl->state;
  530. fdm.home = loc;
  531. return true;
  532. } else {
  533. return false;
  534. }
  535. #endif
  536. default:
  537. return false;
  538. }
  539. }
  540. // return true if inertial navigation is active
  541. bool AP_AHRS_NavEKF::have_inertial_nav(void) const
  542. {
  543. return active_EKF_type() != EKF_TYPE_NONE;
  544. }
  545. // return a ground velocity in meters/second, North/East/Down
  546. // order. Must only be called if have_inertial_nav() is true
  547. bool AP_AHRS_NavEKF::get_velocity_NED(Vector3f &vec) const
  548. {
  549. switch (active_EKF_type()) {
  550. case EKF_TYPE_NONE:
  551. return AP_AHRS_DCM::get_velocity_NED(vec);
  552. case EKF_TYPE2:
  553. default:
  554. EKF2.getVelNED(-1,vec);
  555. return true;
  556. case EKF_TYPE3:
  557. EKF3.getVelNED(-1,vec);
  558. return true;
  559. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  560. case EKF_TYPE_SITL:
  561. if (!_sitl) {
  562. return false;
  563. }
  564. const struct SITL::sitl_fdm &fdm = _sitl->state;
  565. vec = Vector3f(fdm.speedN, fdm.speedE, fdm.speedD);
  566. return true;
  567. #endif
  568. }
  569. }
  570. // returns the expected NED magnetic field
  571. bool AP_AHRS_NavEKF::get_mag_field_NED(Vector3f &vec) const
  572. {
  573. switch (active_EKF_type()) {
  574. case EKF_TYPE_NONE:
  575. return false;
  576. case EKF_TYPE2:
  577. default:
  578. EKF2.getMagNED(-1,vec);
  579. return true;
  580. case EKF_TYPE3:
  581. EKF3.getMagNED(-1,vec);
  582. return true;
  583. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  584. case EKF_TYPE_SITL:
  585. return false;
  586. #endif
  587. }
  588. }
  589. // returns the estimated magnetic field offsets in body frame
  590. bool AP_AHRS_NavEKF::get_mag_field_correction(Vector3f &vec) const
  591. {
  592. switch (active_EKF_type()) {
  593. case EKF_TYPE_NONE:
  594. return false;
  595. case EKF_TYPE2:
  596. default:
  597. EKF2.getMagXYZ(-1,vec);
  598. return true;
  599. case EKF_TYPE3:
  600. EKF3.getMagXYZ(-1,vec);
  601. return true;
  602. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  603. case EKF_TYPE_SITL:
  604. return false;
  605. #endif
  606. }
  607. }
  608. // Get a derivative of the vertical position which is kinematically consistent with the vertical position is required by some control loops.
  609. // This is different to the vertical velocity from the EKF which is not always consistent with the verical position due to the various errors that are being corrected for.
  610. bool AP_AHRS_NavEKF::get_vert_pos_rate(float &velocity) const
  611. {
  612. switch (active_EKF_type()) {
  613. case EKF_TYPE_NONE:
  614. return false;
  615. case EKF_TYPE2:
  616. default:
  617. velocity = EKF2.getPosDownDerivative(-1);
  618. return true;
  619. case EKF_TYPE3:
  620. velocity = EKF3.getPosDownDerivative(-1);
  621. return true;
  622. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  623. case EKF_TYPE_SITL:
  624. if (_sitl) {
  625. const struct SITL::sitl_fdm &fdm = _sitl->state;
  626. velocity = fdm.speedD;
  627. return true;
  628. } else {
  629. return false;
  630. }
  631. #endif
  632. }
  633. }
  634. // get latest height above ground level estimate in metres and a validity flag
  635. bool AP_AHRS_NavEKF::get_hagl(float &height) const
  636. {
  637. switch (active_EKF_type()) {
  638. case EKF_TYPE_NONE:
  639. return false;
  640. case EKF_TYPE2:
  641. default:
  642. return EKF2.getHAGL(height);
  643. case EKF_TYPE3:
  644. return EKF3.getHAGL(height);
  645. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  646. case EKF_TYPE_SITL: {
  647. if (!_sitl) {
  648. return false;
  649. }
  650. const struct SITL::sitl_fdm &fdm = _sitl->state;
  651. height = fdm.altitude - get_home().alt*0.01f;
  652. return true;
  653. }
  654. #endif
  655. }
  656. }
  657. // return a relative ground position to the origin in meters
  658. // North/East/Down order.
  659. bool AP_AHRS_NavEKF::get_relative_position_NED_origin(Vector3f &vec) const
  660. {
  661. switch (active_EKF_type()) {
  662. case EKF_TYPE_NONE:
  663. return false;
  664. case EKF_TYPE2:
  665. default: {
  666. Vector2f posNE;
  667. float posD;
  668. if (EKF2.getPosNE(-1,posNE) && EKF2.getPosD(-1,posD)) {
  669. // position is valid
  670. vec.x = posNE.x;
  671. vec.y = posNE.y;
  672. vec.z = posD;
  673. return true;
  674. }
  675. return false;
  676. }
  677. case EKF_TYPE3: {
  678. Vector2f posNE;
  679. float posD;
  680. if (EKF3.getPosNE(-1,posNE) && EKF3.getPosD(-1,posD)) {
  681. // position is valid
  682. vec.x = posNE.x;
  683. vec.y = posNE.y;
  684. vec.z = posD;
  685. return true;
  686. }
  687. return false;
  688. }
  689. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  690. case EKF_TYPE_SITL: {
  691. if (!_sitl) {
  692. return false;
  693. }
  694. Location loc;
  695. get_position(loc);
  696. const Vector2f diff2d = get_home().get_distance_NE(loc);
  697. const struct SITL::sitl_fdm &fdm = _sitl->state;
  698. vec = Vector3f(diff2d.x, diff2d.y,
  699. -(fdm.altitude - get_home().alt*0.01f));
  700. return true;
  701. }
  702. #endif
  703. }
  704. }
  705. // return a relative ground position to the home in meters
  706. // North/East/Down order.
  707. bool AP_AHRS_NavEKF::get_relative_position_NED_home(Vector3f &vec) const
  708. {
  709. Location originLLH;
  710. Vector3f originNED;
  711. if (!get_relative_position_NED_origin(originNED) ||
  712. !get_origin(originLLH)) {
  713. return false;
  714. }
  715. const Vector3f offset = originLLH.get_distance_NED(_home);
  716. vec.x = originNED.x - offset.x;
  717. vec.y = originNED.y - offset.y;
  718. vec.z = originNED.z - offset.z;
  719. return true;
  720. }
  721. // write a relative ground position estimate to the origin in meters, North/East order
  722. // return true if estimate is valid
  723. bool AP_AHRS_NavEKF::get_relative_position_NE_origin(Vector2f &posNE) const
  724. {
  725. switch (active_EKF_type()) {
  726. case EKF_TYPE_NONE:
  727. return false;
  728. case EKF_TYPE2:
  729. default: {
  730. bool position_is_valid = EKF2.getPosNE(-1,posNE);
  731. return position_is_valid;
  732. }
  733. case EKF_TYPE3: {
  734. bool position_is_valid = EKF3.getPosNE(-1,posNE);
  735. return position_is_valid;
  736. }
  737. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  738. case EKF_TYPE_SITL: {
  739. Location loc;
  740. get_position(loc);
  741. posNE = get_home().get_distance_NE(loc);
  742. return true;
  743. }
  744. #endif
  745. }
  746. }
  747. // return a relative ground position to the home in meters
  748. // North/East order.
  749. bool AP_AHRS_NavEKF::get_relative_position_NE_home(Vector2f &posNE) const
  750. {
  751. Location originLLH;
  752. Vector2f originNE;
  753. if (!get_relative_position_NE_origin(originNE) ||
  754. !get_origin(originLLH)) {
  755. return false;
  756. }
  757. const Vector2f offset = originLLH.get_distance_NE(_home);
  758. posNE.x = originNE.x - offset.x;
  759. posNE.y = originNE.y - offset.y;
  760. return true;
  761. }
  762. // write a relative ground position estimate to the origin in meters, North/East order
  763. // write a relative ground position to the origin in meters, Down
  764. // return true if the estimate is valid
  765. bool AP_AHRS_NavEKF::get_relative_position_D_origin(float &posD) const
  766. {
  767. switch (active_EKF_type()) {
  768. case EKF_TYPE_NONE:
  769. return false;
  770. case EKF_TYPE2:
  771. default: {
  772. bool position_is_valid = EKF2.getPosD(-1,posD);
  773. return position_is_valid;
  774. }
  775. case EKF_TYPE3: {
  776. bool position_is_valid = EKF3.getPosD(-1,posD);
  777. return position_is_valid;
  778. }
  779. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  780. case EKF_TYPE_SITL: {
  781. if (!_sitl) {
  782. return false;
  783. }
  784. const struct SITL::sitl_fdm &fdm = _sitl->state;
  785. posD = -(fdm.altitude - get_home().alt*0.01f);
  786. return true;
  787. }
  788. #endif
  789. }
  790. }
  791. // write a relative ground position to home in meters, Down
  792. // will use the barometer if the EKF isn't available
  793. void AP_AHRS_NavEKF::get_relative_position_D_home(float &posD) const
  794. {
  795. Location originLLH;
  796. float originD;
  797. if (!get_relative_position_D_origin(originD) ||
  798. !get_origin(originLLH)) {
  799. posD = -AP::baro().get_altitude();
  800. return;
  801. }
  802. posD = originD - ((originLLH.alt - _home.alt) * 0.01f);
  803. return;
  804. }
  805. /*
  806. canonicalise _ekf_type, forcing it to be 0, 2 or 3
  807. type 1 has been deprecated
  808. */
  809. uint8_t AP_AHRS_NavEKF::ekf_type(void) const
  810. {
  811. uint8_t type = _ekf_type;
  812. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  813. if (type == EKF_TYPE_SITL) {
  814. return type;
  815. }
  816. #endif
  817. if ((always_use_EKF() && (type == 0)) || (type == 1) || (type > 3)) {
  818. type = 2;
  819. }
  820. return type;
  821. }
  822. AP_AHRS_NavEKF::EKF_TYPE AP_AHRS_NavEKF::active_EKF_type(void) const
  823. {
  824. EKF_TYPE ret = EKF_TYPE_NONE;
  825. switch (ekf_type()) {
  826. case 0:
  827. return EKF_TYPE_NONE;
  828. case 2: {
  829. // do we have an EKF2 yet?
  830. if (!_ekf2_started) {
  831. return EKF_TYPE_NONE;
  832. }
  833. if (always_use_EKF()) {
  834. uint16_t ekf2_faults;
  835. EKF2.getFilterFaults(-1,ekf2_faults);
  836. if (ekf2_faults == 0) {
  837. ret = EKF_TYPE2;
  838. }
  839. } else if (EKF2.healthy()) {
  840. ret = EKF_TYPE2;
  841. }
  842. break;
  843. }
  844. case 3: {
  845. // do we have an EKF3 yet?
  846. if (!_ekf3_started) {
  847. return EKF_TYPE_NONE;
  848. }
  849. if (always_use_EKF()) {
  850. uint16_t ekf3_faults;
  851. EKF3.getFilterFaults(-1,ekf3_faults);
  852. if (ekf3_faults == 0) {
  853. ret = EKF_TYPE3;
  854. }
  855. } else if (EKF3.healthy()) {
  856. ret = EKF_TYPE3;
  857. }
  858. break;
  859. }
  860. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  861. case EKF_TYPE_SITL:
  862. ret = EKF_TYPE_SITL;
  863. break;
  864. #endif
  865. }
  866. /*
  867. fixed wing and rover when in fly_forward mode will fall back to
  868. DCM if the EKF doesn't have GPS. This is the safest option as
  869. DCM is very robust. Note that we also check the filter status
  870. when fly_forward is false and we are disarmed. This is to ensure
  871. that the arming checks do wait for good GPS position on fixed
  872. wing and rover
  873. */
  874. if (ret != EKF_TYPE_NONE &&
  875. (_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
  876. _vehicle_class == AHRS_VEHICLE_GROUND) &&
  877. (_flags.fly_forward || !hal.util->get_soft_armed())) {
  878. nav_filter_status filt_state;
  879. if (ret == EKF_TYPE2) {
  880. EKF2.getFilterStatus(-1,filt_state);
  881. } else if (ret == EKF_TYPE3) {
  882. EKF3.getFilterStatus(-1,filt_state);
  883. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  884. } else if (ret == EKF_TYPE_SITL) {
  885. get_filter_status(filt_state);
  886. #endif
  887. }
  888. if (hal.util->get_soft_armed() && !filt_state.flags.using_gps && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
  889. // if the EKF is not fusing GPS and we have a 3D lock, then
  890. // plane and rover would prefer to use the GPS position from
  891. // DCM. This is a safety net while some issues with the EKF
  892. // get sorted out
  893. return EKF_TYPE_NONE;
  894. }
  895. if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
  896. return EKF_TYPE_NONE;
  897. }
  898. if (!filt_state.flags.attitude ||
  899. !filt_state.flags.vert_vel ||
  900. !filt_state.flags.vert_pos) {
  901. return EKF_TYPE_NONE;
  902. }
  903. if (!filt_state.flags.horiz_vel ||
  904. (!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) {
  905. if ((!_compass || !_compass->use_for_yaw()) &&
  906. AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&
  907. AP::gps().ground_speed() < 2) {
  908. /*
  909. special handling for non-compass mode when sitting
  910. still. The EKF may not yet have aligned its yaw. We
  911. accept EKF as healthy to allow arming. Once we reach
  912. speed the EKF should get yaw alignment
  913. */
  914. if (filt_state.flags.gps_quality_good) {
  915. return ret;
  916. }
  917. }
  918. return EKF_TYPE_NONE;
  919. }
  920. }
  921. return ret;
  922. }
  923. /*
  924. check if the AHRS subsystem is healthy
  925. */
  926. bool AP_AHRS_NavEKF::healthy(void) const
  927. {
  928. // If EKF is started we switch away if it reports unhealthy. This could be due to bad
  929. // sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters
  930. // an internal processing error, but not for bad sensor data.
  931. switch (ekf_type()) {
  932. case 0:
  933. return AP_AHRS_DCM::healthy();
  934. case 2: {
  935. bool ret = _ekf2_started && EKF2.healthy();
  936. if (!ret) {
  937. return false;
  938. }
  939. if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
  940. _vehicle_class == AHRS_VEHICLE_GROUND) &&
  941. active_EKF_type() != EKF_TYPE2) {
  942. // on fixed wing we want to be using EKF to be considered
  943. // healthy if EKF is enabled
  944. return false;
  945. }
  946. return true;
  947. }
  948. case 3: {
  949. bool ret = _ekf3_started && EKF3.healthy();
  950. if (!ret) {
  951. return false;
  952. }
  953. if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
  954. _vehicle_class == AHRS_VEHICLE_GROUND) &&
  955. active_EKF_type() != EKF_TYPE3) {
  956. // on fixed wing we want to be using EKF to be considered
  957. // healthy if EKF is enabled
  958. return false;
  959. }
  960. return true;
  961. }
  962. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  963. case EKF_TYPE_SITL:
  964. return true;
  965. #endif
  966. }
  967. return AP_AHRS_DCM::healthy();
  968. }
  969. bool AP_AHRS_NavEKF::prearm_healthy(void) const
  970. {
  971. bool prearm_health = false;
  972. switch (ekf_type()) {
  973. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  974. case EKF_TYPE_SITL:
  975. #endif
  976. case EKF_TYPE_NONE:
  977. prearm_health = true;
  978. break;
  979. case EKF_TYPE2:
  980. default:
  981. if (_ekf2_started && EKF2.all_cores_healthy()) {
  982. prearm_health = true;
  983. }
  984. break;
  985. case EKF_TYPE3:
  986. if (_ekf3_started && EKF3.all_cores_healthy()) {
  987. prearm_health = true;
  988. }
  989. break;
  990. }
  991. return prearm_health && healthy();
  992. }
  993. void AP_AHRS_NavEKF::set_ekf_use(bool setting)
  994. {
  995. _ekf_type.set(setting?1:0);
  996. }
  997. // true if the AHRS has completed initialisation
  998. bool AP_AHRS_NavEKF::initialised(void) const
  999. {
  1000. switch (ekf_type()) {
  1001. case 0:
  1002. return true;
  1003. case 2:
  1004. default:
  1005. // initialisation complete 10sec after ekf has started
  1006. return (_ekf2_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
  1007. case 3:
  1008. // initialisation complete 10sec after ekf has started
  1009. return (_ekf3_started && (AP_HAL::millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
  1010. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1011. case EKF_TYPE_SITL:
  1012. return true;
  1013. #endif
  1014. }
  1015. };
  1016. // get_filter_status : returns filter status as a series of flags
  1017. bool AP_AHRS_NavEKF::get_filter_status(nav_filter_status &status) const
  1018. {
  1019. switch (ekf_type()) {
  1020. case EKF_TYPE_NONE:
  1021. return false;
  1022. case EKF_TYPE2:
  1023. default:
  1024. EKF2.getFilterStatus(-1,status);
  1025. return true;
  1026. case EKF_TYPE3:
  1027. EKF3.getFilterStatus(-1,status);
  1028. return true;
  1029. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1030. case EKF_TYPE_SITL:
  1031. memset(&status, 0, sizeof(status));
  1032. status.flags.attitude = 1;
  1033. status.flags.horiz_vel = 1;
  1034. status.flags.vert_vel = 1;
  1035. status.flags.horiz_pos_rel = 1;
  1036. status.flags.horiz_pos_abs = 1;
  1037. status.flags.vert_pos = 1;
  1038. status.flags.pred_horiz_pos_rel = 1;
  1039. status.flags.pred_horiz_pos_abs = 1;
  1040. status.flags.using_gps = 1;
  1041. return true;
  1042. #endif
  1043. }
  1044. }
  1045. // write optical flow data to EKF
  1046. void AP_AHRS_NavEKF::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
  1047. {
  1048. EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
  1049. EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
  1050. }
  1051. // write body frame odometry measurements to the EKF
  1052. void AP_AHRS_NavEKF::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
  1053. {
  1054. EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
  1055. }
  1056. // Write position and quaternion data from an external navigation system
  1057. void AP_AHRS_NavEKF::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
  1058. {
  1059. EKF2.writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
  1060. }
  1061. // inhibit GPS usage
  1062. uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
  1063. {
  1064. switch (ekf_type()) {
  1065. case 0:
  1066. case 2:
  1067. default:
  1068. return EKF2.setInhibitGPS();
  1069. case 3:
  1070. return EKF3.setInhibitGPS();
  1071. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1072. case EKF_TYPE_SITL:
  1073. return false;
  1074. #endif
  1075. }
  1076. }
  1077. // get speed limit
  1078. void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
  1079. {
  1080. switch (ekf_type()) {
  1081. case 0:
  1082. case 2:
  1083. EKF2.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
  1084. break;
  1085. case 3:
  1086. EKF3.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
  1087. break;
  1088. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1089. case EKF_TYPE_SITL:
  1090. // same as EKF2 for no optical flow
  1091. ekfGndSpdLimit = 400.0f;
  1092. ekfNavVelGainScaler = 1.0f;
  1093. break;
  1094. #endif
  1095. }
  1096. }
  1097. // get compass offset estimates
  1098. // true if offsets are valid
  1099. bool AP_AHRS_NavEKF::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
  1100. {
  1101. switch (ekf_type()) {
  1102. case 0:
  1103. case 2:
  1104. default:
  1105. return EKF2.getMagOffsets(mag_idx, magOffsets);
  1106. case 3:
  1107. return EKF3.getMagOffsets(mag_idx, magOffsets);
  1108. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1109. case EKF_TYPE_SITL:
  1110. magOffsets.zero();
  1111. return true;
  1112. #endif
  1113. }
  1114. }
  1115. // Retrieves the NED delta velocity corrected
  1116. void AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const
  1117. {
  1118. const EKF_TYPE type = active_EKF_type();
  1119. if (type == EKF_TYPE2 || type == EKF_TYPE3) {
  1120. int8_t imu_idx = 0;
  1121. Vector3f accel_bias;
  1122. if (type == EKF_TYPE2) {
  1123. accel_bias.zero();
  1124. imu_idx = EKF2.getPrimaryCoreIMUIndex();
  1125. EKF2.getAccelZBias(-1,accel_bias.z);
  1126. } else if (type == EKF_TYPE3) {
  1127. imu_idx = EKF3.getPrimaryCoreIMUIndex();
  1128. EKF3.getAccelBias(-1,accel_bias);
  1129. }
  1130. if (imu_idx == -1) {
  1131. // should never happen, call parent implementation in this scenario
  1132. AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt);
  1133. return;
  1134. }
  1135. ret.zero();
  1136. const AP_InertialSensor &_ins = AP::ins();
  1137. _ins.get_delta_velocity((uint8_t)imu_idx, ret);
  1138. dt = _ins.get_delta_velocity_dt((uint8_t)imu_idx);
  1139. ret -= accel_bias*dt;
  1140. ret = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret;
  1141. ret.z += GRAVITY_MSS*dt;
  1142. } else {
  1143. AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt);
  1144. }
  1145. }
  1146. // report any reason for why the backend is refusing to initialise
  1147. const char *AP_AHRS_NavEKF::prearm_failure_reason(void) const
  1148. {
  1149. switch (ekf_type()) {
  1150. case 0:
  1151. return nullptr;
  1152. case 2:
  1153. default:
  1154. return EKF2.prearm_failure_reason();
  1155. case 3:
  1156. return EKF3.prearm_failure_reason();
  1157. }
  1158. return nullptr;
  1159. }
  1160. // check all cores providing consistent attitudes for prearm checks
  1161. bool AP_AHRS_NavEKF::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const
  1162. {
  1163. // get primary attitude source's attitude as quaternion
  1164. Quaternion primary_quat;
  1165. get_quat_body_to_ned(primary_quat);
  1166. // only check yaw if compasses are being used
  1167. bool check_yaw = _compass && _compass->use_for_yaw();
  1168. // check primary vs ekf2
  1169. for (uint8_t i = 0; i < EKF2.activeCores(); i++) {
  1170. Quaternion ekf2_quat;
  1171. Vector3f angle_diff;
  1172. EKF2.getQuaternionBodyToNED(i, ekf2_quat);
  1173. primary_quat.angular_difference(ekf2_quat).to_axis_angle(angle_diff);
  1174. float diff = safe_sqrt(sq(angle_diff.x)+sq(angle_diff.y));
  1175. if (diff > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
  1176. hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 Roll/Pitch inconsistent by %d deg", (int)degrees(diff));
  1177. return false;
  1178. }
  1179. diff = fabsf(angle_diff.z);
  1180. if (check_yaw && (diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
  1181. hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 Yaw inconsistent by %d deg", (int)degrees(diff));
  1182. return false;
  1183. }
  1184. }
  1185. // check primary vs ekf3
  1186. for (uint8_t i = 0; i < EKF3.activeCores(); i++) {
  1187. Quaternion ekf3_quat;
  1188. Vector3f angle_diff;
  1189. EKF3.getQuaternionBodyToNED(i, ekf3_quat);
  1190. primary_quat.angular_difference(ekf3_quat).to_axis_angle(angle_diff);
  1191. float diff = safe_sqrt(sq(angle_diff.x)+sq(angle_diff.y));
  1192. if (diff > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
  1193. hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 Roll/Pitch inconsistent by %d deg", (int)degrees(diff));
  1194. return false;
  1195. }
  1196. diff = fabsf(angle_diff.z);
  1197. if (check_yaw && (diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
  1198. hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 Yaw inconsistent by %d deg", (int)degrees(diff));
  1199. return false;
  1200. }
  1201. }
  1202. // check primary vs dcm
  1203. Quaternion dcm_quat;
  1204. Vector3f angle_diff;
  1205. dcm_quat.from_rotation_matrix(get_DCM_rotation_body_to_ned());
  1206. primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff);
  1207. float diff = safe_sqrt(sq(angle_diff.x)+sq(angle_diff.y));
  1208. if (diff > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) {
  1209. hal.util->snprintf(failure_msg, failure_msg_len, "DCM Roll/Pitch inconsistent by %d deg", (int)degrees(diff));
  1210. return false;
  1211. }
  1212. diff = fabsf(angle_diff.z);
  1213. if (check_yaw && (diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) {
  1214. hal.util->snprintf(failure_msg, failure_msg_len, "DCM Yaw inconsistent by %d deg", (int)degrees(diff));
  1215. return false;
  1216. }
  1217. return true;
  1218. }
  1219. // return the amount of yaw angle change due to the last yaw angle reset in radians
  1220. // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
  1221. uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) const
  1222. {
  1223. switch (ekf_type()) {
  1224. case 2:
  1225. default:
  1226. return EKF2.getLastYawResetAngle(yawAng);
  1227. case 3:
  1228. return EKF3.getLastYawResetAngle(yawAng);
  1229. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1230. case EKF_TYPE_SITL:
  1231. return 0;
  1232. #endif
  1233. }
  1234. return 0;
  1235. }
  1236. // return the amount of NE position change in metres due to the last reset
  1237. // returns the time of the last reset or 0 if no reset has ever occurred
  1238. uint32_t AP_AHRS_NavEKF::getLastPosNorthEastReset(Vector2f &pos) const
  1239. {
  1240. switch (ekf_type()) {
  1241. case 2:
  1242. default:
  1243. return EKF2.getLastPosNorthEastReset(pos);
  1244. case 3:
  1245. return EKF3.getLastPosNorthEastReset(pos);
  1246. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1247. case EKF_TYPE_SITL:
  1248. return 0;
  1249. #endif
  1250. }
  1251. return 0;
  1252. }
  1253. // return the amount of NE velocity change in metres/sec due to the last reset
  1254. // returns the time of the last reset or 0 if no reset has ever occurred
  1255. uint32_t AP_AHRS_NavEKF::getLastVelNorthEastReset(Vector2f &vel) const
  1256. {
  1257. switch (ekf_type()) {
  1258. case 2:
  1259. default:
  1260. return EKF2.getLastVelNorthEastReset(vel);
  1261. case 3:
  1262. return EKF3.getLastVelNorthEastReset(vel);
  1263. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1264. case EKF_TYPE_SITL:
  1265. return 0;
  1266. #endif
  1267. }
  1268. return 0;
  1269. }
  1270. // return the amount of vertical position change due to the last reset in meters
  1271. // returns the time of the last reset or 0 if no reset has ever occurred
  1272. uint32_t AP_AHRS_NavEKF::getLastPosDownReset(float &posDelta) const
  1273. {
  1274. switch (ekf_type()) {
  1275. case EKF_TYPE2:
  1276. return EKF2.getLastPosDownReset(posDelta);
  1277. case EKF_TYPE3:
  1278. return EKF3.getLastPosDownReset(posDelta);
  1279. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1280. case EKF_TYPE_SITL:
  1281. return 0;
  1282. #endif
  1283. }
  1284. return 0;
  1285. }
  1286. // Resets the baro so that it reads zero at the current height
  1287. // Resets the EKF height to zero
  1288. // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
  1289. // Returns true if the height datum reset has been performed
  1290. // If using a range finder for height no reset is performed and it returns false
  1291. bool AP_AHRS_NavEKF::resetHeightDatum(void)
  1292. {
  1293. // support locked access functions to AHRS data
  1294. WITH_SEMAPHORE(_rsem);
  1295. switch (ekf_type()) {
  1296. case 2:
  1297. default: {
  1298. EKF3.resetHeightDatum();
  1299. return EKF2.resetHeightDatum();
  1300. }
  1301. case 3: {
  1302. EKF2.resetHeightDatum();
  1303. return EKF3.resetHeightDatum();
  1304. }
  1305. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1306. case EKF_TYPE_SITL:
  1307. return false;
  1308. #endif
  1309. }
  1310. return false;
  1311. }
  1312. // send a EKF_STATUS_REPORT for current EKF
  1313. void AP_AHRS_NavEKF::send_ekf_status_report(mavlink_channel_t chan) const
  1314. {
  1315. switch (ekf_type()) {
  1316. case EKF_TYPE_NONE:
  1317. // send zero status report
  1318. mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0);
  1319. break;
  1320. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1321. case EKF_TYPE_SITL:
  1322. {
  1323. // send status report with everything looking good
  1324. const uint16_t flags =
  1325. EKF_ATTITUDE | /* Set if EKF's attitude estimate is good. | */
  1326. EKF_VELOCITY_HORIZ | /* Set if EKF's horizontal velocity estimate is good. | */
  1327. EKF_VELOCITY_VERT | /* Set if EKF's vertical velocity estimate is good. | */
  1328. EKF_POS_HORIZ_REL | /* Set if EKF's horizontal position (relative) estimate is good. | */
  1329. EKF_POS_HORIZ_ABS | /* Set if EKF's horizontal position (absolute) estimate is good. | */
  1330. EKF_POS_VERT_ABS | /* Set if EKF's vertical position (absolute) estimate is good. | */
  1331. EKF_POS_VERT_AGL | /* Set if EKF's vertical position (above ground) estimate is good. | */
  1332. //EKF_CONST_POS_MODE | /* EKF is in constant position mode and does not know it's absolute or relative position. | */
  1333. EKF_PRED_POS_HORIZ_REL | /* Set if EKF's predicted horizontal position (relative) estimate is good. | */
  1334. EKF_PRED_POS_HORIZ_ABS; /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */
  1335. mavlink_msg_ekf_status_report_send(chan, flags, 0, 0, 0, 0, 0, 0);
  1336. }
  1337. break;
  1338. #endif
  1339. case EKF_TYPE2:
  1340. return EKF2.send_status_report(chan);
  1341. case EKF_TYPE3:
  1342. return EKF3.send_status_report(chan);
  1343. }
  1344. }
  1345. // passes a reference to the location of the inertial navigation origin
  1346. // in WGS-84 coordinates
  1347. // returns a boolean true when the inertial navigation origin has been set
  1348. bool AP_AHRS_NavEKF::get_origin(Location &ret) const
  1349. {
  1350. switch (ekf_type()) {
  1351. case EKF_TYPE_NONE:
  1352. return false;
  1353. case EKF_TYPE2:
  1354. default:
  1355. if (!EKF2.getOriginLLH(-1,ret)) {
  1356. return false;
  1357. }
  1358. return true;
  1359. case EKF_TYPE3:
  1360. if (!EKF3.getOriginLLH(-1,ret)) {
  1361. return false;
  1362. }
  1363. return true;
  1364. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1365. case EKF_TYPE_SITL:
  1366. if (!_sitl) {
  1367. return false;
  1368. }
  1369. const struct SITL::sitl_fdm &fdm = _sitl->state;
  1370. ret = fdm.home;
  1371. return true;
  1372. #endif
  1373. }
  1374. }
  1375. // get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag
  1376. // this is used to limit height during optical flow navigation
  1377. // it will return false when no limiting is required
  1378. bool AP_AHRS_NavEKF::get_hgt_ctrl_limit(float& limit) const
  1379. {
  1380. switch (ekf_type()) {
  1381. case EKF_TYPE_NONE:
  1382. // We are not using an EKF so no limiting applies
  1383. return false;
  1384. case EKF_TYPE2:
  1385. default:
  1386. return EKF2.getHeightControlLimit(limit);
  1387. case EKF_TYPE3:
  1388. return EKF3.getHeightControlLimit(limit);
  1389. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1390. case EKF_TYPE_SITL:
  1391. return false;
  1392. #endif
  1393. }
  1394. }
  1395. // get_location - updates the provided location with the latest calculated location
  1396. // returns true on success (i.e. the EKF knows it's latest position), false on failure
  1397. bool AP_AHRS_NavEKF::get_location(struct Location &loc) const
  1398. {
  1399. switch (ekf_type()) {
  1400. case EKF_TYPE_NONE:
  1401. // We are not using an EKF so no data
  1402. return false;
  1403. case EKF_TYPE2:
  1404. default:
  1405. return EKF2.getLLH(loc);
  1406. case EKF_TYPE3:
  1407. return EKF3.getLLH(loc);
  1408. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1409. case EKF_TYPE_SITL:
  1410. return get_position(loc);
  1411. #endif
  1412. }
  1413. }
  1414. // get_variances - provides the innovations normalised using the innovation variance where a value of 0
  1415. // indicates prefect consistency between the measurement and the EKF solution and a value of of 1 is the maximum
  1416. // inconsistency that will be accpeted by the filter
  1417. // boolean false is returned if variances are not available
  1418. bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
  1419. {
  1420. switch (ekf_type()) {
  1421. case EKF_TYPE_NONE:
  1422. // We are not using an EKF so no data
  1423. return false;
  1424. case EKF_TYPE2:
  1425. default:
  1426. // use EKF to get variance
  1427. EKF2.getVariances(-1,velVar, posVar, hgtVar, magVar, tasVar, offset);
  1428. return true;
  1429. case EKF_TYPE3:
  1430. // use EKF to get variance
  1431. EKF3.getVariances(-1,velVar, posVar, hgtVar, magVar, tasVar, offset);
  1432. return true;
  1433. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1434. case EKF_TYPE_SITL:
  1435. velVar = 0;
  1436. posVar = 0;
  1437. hgtVar = 0;
  1438. magVar.zero();
  1439. tasVar = 0;
  1440. offset.zero();
  1441. return true;
  1442. #endif
  1443. }
  1444. }
  1445. void AP_AHRS_NavEKF::setTakeoffExpected(bool val)
  1446. {
  1447. switch (ekf_type()) {
  1448. case EKF_TYPE2:
  1449. default:
  1450. EKF2.setTakeoffExpected(val);
  1451. break;
  1452. case EKF_TYPE3:
  1453. EKF3.setTakeoffExpected(val);
  1454. break;
  1455. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1456. case EKF_TYPE_SITL:
  1457. break;
  1458. #endif
  1459. }
  1460. }
  1461. void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
  1462. {
  1463. switch (ekf_type()) {
  1464. case EKF_TYPE2:
  1465. default:
  1466. EKF2.setTouchdownExpected(val);
  1467. break;
  1468. case EKF_TYPE3:
  1469. EKF3.setTouchdownExpected(val);
  1470. break;
  1471. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1472. case EKF_TYPE_SITL:
  1473. break;
  1474. #endif
  1475. }
  1476. }
  1477. bool AP_AHRS_NavEKF::getGpsGlitchStatus() const
  1478. {
  1479. nav_filter_status ekf_status {};
  1480. if (!get_filter_status(ekf_status)) {
  1481. return false;
  1482. }
  1483. return ekf_status.flags.gps_glitching;
  1484. }
  1485. // is the EKF backend doing its own sensor logging?
  1486. bool AP_AHRS_NavEKF::have_ekf_logging(void) const
  1487. {
  1488. switch (ekf_type()) {
  1489. case 2:
  1490. return EKF2.have_ekf_logging();
  1491. case 3:
  1492. return EKF3.have_ekf_logging();
  1493. default:
  1494. break;
  1495. }
  1496. return false;
  1497. }
  1498. // get the index of the current primary IMU
  1499. uint8_t AP_AHRS_NavEKF::get_primary_IMU_index() const
  1500. {
  1501. int8_t imu = -1;
  1502. switch (ekf_type()) {
  1503. case 2:
  1504. // let EKF2 choose primary IMU
  1505. imu = EKF2.getPrimaryCoreIMUIndex();
  1506. break;
  1507. case 3:
  1508. // let EKF2 choose primary IMU
  1509. imu = EKF3.getPrimaryCoreIMUIndex();
  1510. break;
  1511. default:
  1512. break;
  1513. }
  1514. if (imu == -1) {
  1515. imu = AP::ins().get_primary_accel();
  1516. }
  1517. return imu;
  1518. }
  1519. // get earth-frame accel vector for primary IMU
  1520. const Vector3f &AP_AHRS_NavEKF::get_accel_ef() const
  1521. {
  1522. return get_accel_ef(get_primary_accel_index());
  1523. }
  1524. // get the index of the current primary accelerometer sensor
  1525. uint8_t AP_AHRS_NavEKF::get_primary_accel_index(void) const
  1526. {
  1527. if (ekf_type() != 0) {
  1528. return get_primary_IMU_index();
  1529. }
  1530. return AP::ins().get_primary_accel();
  1531. }
  1532. // get the index of the current primary gyro sensor
  1533. uint8_t AP_AHRS_NavEKF::get_primary_gyro_index(void) const
  1534. {
  1535. if (ekf_type() != 0) {
  1536. return get_primary_IMU_index();
  1537. }
  1538. return AP::ins().get_primary_gyro();
  1539. }
  1540. // see if EKF lane switching is possible to avoid EKF failsafe
  1541. void AP_AHRS_NavEKF::check_lane_switch(void)
  1542. {
  1543. switch (active_EKF_type()) {
  1544. case EKF_TYPE_NONE:
  1545. break;
  1546. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1547. case EKF_TYPE_SITL:
  1548. break;
  1549. #endif
  1550. case EKF_TYPE2:
  1551. EKF2.checkLaneSwitch();
  1552. break;
  1553. case EKF_TYPE3:
  1554. EKF3.checkLaneSwitch();
  1555. break;
  1556. }
  1557. }
  1558. void AP_AHRS_NavEKF::Log_Write()
  1559. {
  1560. get_NavEKF2().Log_Write();
  1561. get_NavEKF3().Log_Write();
  1562. }
  1563. AP_AHRS_NavEKF &AP::ahrs_navekf()
  1564. {
  1565. return static_cast<AP_AHRS_NavEKF&>(*AP_AHRS::get_singleton());
  1566. }
  1567. // check whether compass can be bypassed for arming check in case when external navigation data is available
  1568. bool AP_AHRS_NavEKF::is_ext_nav_used_for_yaw(void) const
  1569. {
  1570. switch (active_EKF_type()) {
  1571. case EKF_TYPE2:
  1572. return EKF2.isExtNavUsedForYaw();
  1573. default:
  1574. return false;
  1575. }
  1576. }
  1577. #endif // AP_AHRS_NAVEKF_AVAILABLE