AP_NavEKF2_VehicleStatus.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_NavEKF2.h"
  3. #include "AP_NavEKF2_core.h"
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <AP_Vehicle/AP_Vehicle.h>
  6. #include <GCS_MAVLink/GCS.h>
  7. #include <AP_GPS/AP_GPS.h>
  8. #include <stdio.h>
  9. extern const AP_HAL::HAL& hal;
  10. /* Monitor GPS data to see if quality is good enough to initialise the EKF
  11. Monitor magnetometer innovations to see if the heading is good enough to use GPS
  12. Return true if all criteria pass for 10 seconds
  13. We also record the failure reason so that prearm_failure_reason()
  14. can give a good report to the user on why arming is failing
  15. This sets gpsGoodToAlign class variable
  16. */
  17. void NavEKF2_core::calcGpsGoodToAlign(void)
  18. {
  19. const AP_GPS &gps = AP::gps();
  20. if (inFlight && assume_zero_sideslip() && !use_compass()) {
  21. // this is a special case where a plane has launched without magnetometer
  22. // is now in the air and needs to align yaw to the GPS and start navigating as soon as possible
  23. gpsGoodToAlign = true;
  24. return;
  25. }
  26. // User defined multiplier to be applied to check thresholds
  27. float checkScaler = 0.01f*(float)frontend->_gpsCheckScaler;
  28. if (gpsGoodToAlign) {
  29. /*
  30. if we have already passed GPS alignment checks then raise
  31. the check threshold so that we have some hysterisis and
  32. don't continuously change from able to arm to not able to
  33. arm
  34. */
  35. checkScaler *= 1.3f;
  36. }
  37. // If we have good magnetometer consistency and bad innovations for longer than 5 seconds then we reset heading and field states
  38. // This enables us to handle large changes to the external magnetic field environment that occur before arming
  39. if ((magTestRatio.x <= 1.0f && magTestRatio.y <= 1.0f && yawTestRatio <= 1.0f) || !consistentMagData) {
  40. magYawResetTimer_ms = imuSampleTime_ms;
  41. }
  42. if ((imuSampleTime_ms - magYawResetTimer_ms > 5000) && !motorsArmed) {
  43. // request reset of heading and magnetic field states
  44. magYawResetRequest = true;
  45. // reset timer to ensure that bad magnetometer data cannot cause a heading reset more often than every 5 seconds
  46. magYawResetTimer_ms = imuSampleTime_ms;
  47. }
  48. // Check for significant change in GPS position if disarmed which indicates bad GPS
  49. // This check can only be used when the vehicle is stationary
  50. const struct Location &gpsloc = gps.location(); // Current location
  51. const float posFiltTimeConst = 10.0f; // time constant used to decay position drift
  52. // calculate time lapsed since last update and limit to prevent numerical errors
  53. float deltaTime = constrain_float(float(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst);
  54. lastPreAlignGpsCheckTime_ms = imuDataDelayed.time_ms;
  55. // Sum distance moved
  56. gpsDriftNE += gpsloc_prev.get_distance(gpsloc);
  57. gpsloc_prev = gpsloc;
  58. // Decay distance moved exponentially to zero
  59. gpsDriftNE *= (1.0f - deltaTime/posFiltTimeConst);
  60. // Clamp the filter state to prevent excessive persistence of large transients
  61. gpsDriftNE = MIN(gpsDriftNE,10.0f);
  62. // Fail if more than 3 metres drift after filtering whilst on-ground
  63. // This corresponds to a maximum acceptable average drift rate of 0.3 m/s or single glitch event of 3m
  64. bool gpsDriftFail = (gpsDriftNE > 3.0f*checkScaler) && onGround && (frontend->_gpsCheck & MASK_GPS_POS_DRIFT);
  65. // Report check result as a text string and bitmask
  66. if (gpsDriftFail) {
  67. hal.util->snprintf(prearm_fail_string,
  68. sizeof(prearm_fail_string),
  69. "GPS drift %.1fm (needs %.1f)", (double)gpsDriftNE, (double)(3.0f*checkScaler));
  70. gpsCheckStatus.bad_horiz_drift = true;
  71. } else {
  72. gpsCheckStatus.bad_horiz_drift = false;
  73. }
  74. // Check that the vertical GPS vertical velocity is reasonable after noise filtering
  75. bool gpsVertVelFail;
  76. if (gps.have_vertical_velocity() && onGround) {
  77. // check that the average vertical GPS velocity is close to zero
  78. gpsVertVelFilt = 0.1f * gpsDataNew.vel.z + 0.9f * gpsVertVelFilt;
  79. gpsVertVelFilt = constrain_float(gpsVertVelFilt,-10.0f,10.0f);
  80. gpsVertVelFail = (fabsf(gpsVertVelFilt) > 0.3f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_VERT_SPD);
  81. } else if ((frontend->_fusionModeGPS == 0) && !gps.have_vertical_velocity()) {
  82. // If the EKF settings require vertical GPS velocity and the receiver is not outputting it, then fail
  83. gpsVertVelFail = true;
  84. // if we have a 3D fix with no vertical velocity and
  85. // EK2_GPS_TYPE=0 then change it to 1. It means the GPS is not
  86. // capable of giving a vertical velocity
  87. if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
  88. frontend->_fusionModeGPS.set(1);
  89. gcs().send_text(MAV_SEVERITY_WARNING, "EK2: Changed EK2_GPS_TYPE to 1");
  90. }
  91. } else {
  92. gpsVertVelFail = false;
  93. }
  94. // Report check result as a text string and bitmask
  95. if (gpsVertVelFail) {
  96. hal.util->snprintf(prearm_fail_string,
  97. sizeof(prearm_fail_string),
  98. "GPS vertical speed %.2fm/s (needs %.2f)", (double)fabsf(gpsVertVelFilt), (double)(0.3f*checkScaler));
  99. gpsCheckStatus.bad_vert_vel = true;
  100. } else {
  101. gpsCheckStatus.bad_vert_vel = false;
  102. }
  103. // Check that the horizontal GPS vertical velocity is reasonable after noise filtering
  104. // This check can only be used if the vehicle is stationary
  105. bool gpsHorizVelFail;
  106. if (onGround) {
  107. gpsHorizVelFilt = 0.1f * norm(gpsDataDelayed.vel.x,gpsDataDelayed.vel.y) + 0.9f * gpsHorizVelFilt;
  108. gpsHorizVelFilt = constrain_float(gpsHorizVelFilt,-10.0f,10.0f);
  109. gpsHorizVelFail = (fabsf(gpsHorizVelFilt) > 0.3f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_HORIZ_SPD);
  110. } else {
  111. gpsHorizVelFail = false;
  112. }
  113. // Report check result as a text string and bitmask
  114. if (gpsHorizVelFail) {
  115. hal.util->snprintf(prearm_fail_string,
  116. sizeof(prearm_fail_string),
  117. "GPS horizontal speed %.2fm/s (needs %.2f)", (double)gpsDriftNE, (double)(0.3f*checkScaler));
  118. gpsCheckStatus.bad_horiz_vel = true;
  119. } else {
  120. gpsCheckStatus.bad_horiz_vel = false;
  121. }
  122. // fail if horiziontal position accuracy not sufficient
  123. float hAcc = 0.0f;
  124. bool hAccFail;
  125. if (gps.horizontal_accuracy(hAcc)) {
  126. hAccFail = (hAcc > 5.0f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_POS_ERR);
  127. } else {
  128. hAccFail = false;
  129. }
  130. // Report check result as a text string and bitmask
  131. if (hAccFail) {
  132. hal.util->snprintf(prearm_fail_string,
  133. sizeof(prearm_fail_string),
  134. "GPS horiz error %.1fm (needs %.1f)", (double)hAcc, (double)(5.0f*checkScaler));
  135. gpsCheckStatus.bad_hAcc = true;
  136. } else {
  137. gpsCheckStatus.bad_hAcc = false;
  138. }
  139. // Check for vertical GPS accuracy
  140. float vAcc = 0.0f;
  141. bool vAccFail = false;
  142. if (gps.vertical_accuracy(vAcc)) {
  143. vAccFail = (vAcc > 7.5f * checkScaler) && (frontend->_gpsCheck & MASK_GPS_POS_ERR);
  144. }
  145. // Report check result as a text string and bitmask
  146. if (vAccFail) {
  147. hal.util->snprintf(prearm_fail_string,
  148. sizeof(prearm_fail_string),
  149. "GPS vert error %.1fm (needs < %.1f)", (double)vAcc, (double)(7.5f * checkScaler));
  150. gpsCheckStatus.bad_vAcc = true;
  151. } else {
  152. gpsCheckStatus.bad_vAcc = false;
  153. }
  154. // fail if reported speed accuracy greater than threshold
  155. bool gpsSpdAccFail = (gpsSpdAccuracy > 1.0f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_SPD_ERR);
  156. // Report check result as a text string and bitmask
  157. if (gpsSpdAccFail) {
  158. hal.util->snprintf(prearm_fail_string,
  159. sizeof(prearm_fail_string),
  160. "GPS speed error %.1f (needs < %.1f)", (double)gpsSpdAccuracy, (double)(1.0f*checkScaler));
  161. gpsCheckStatus.bad_sAcc = true;
  162. } else {
  163. gpsCheckStatus.bad_sAcc = false;
  164. }
  165. // fail if satellite geometry is poor
  166. bool hdopFail = (gps.get_hdop() > 250) && (frontend->_gpsCheck & MASK_GPS_HDOP);
  167. // Report check result as a text string and bitmask
  168. if (hdopFail) {
  169. hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string),
  170. "GPS HDOP %.1f (needs 2.5)", (double)(0.01f * gps.get_hdop()));
  171. gpsCheckStatus.bad_hdop = true;
  172. } else {
  173. gpsCheckStatus.bad_hdop = false;
  174. }
  175. // fail if not enough sats
  176. bool numSatsFail = (gps.num_sats() < 6) && (frontend->_gpsCheck & MASK_GPS_NSATS);
  177. // Report check result as a text string and bitmask
  178. if (numSatsFail) {
  179. hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string),
  180. "GPS numsats %u (needs 6)", gps.num_sats());
  181. gpsCheckStatus.bad_sats = true;
  182. } else {
  183. gpsCheckStatus.bad_sats = false;
  184. }
  185. // fail if magnetometer innovations are outside limits indicating bad yaw
  186. // with bad yaw we are unable to use GPS
  187. bool yawFail;
  188. if ((magTestRatio.x > 1.0f || magTestRatio.y > 1.0f || yawTestRatio > 1.0f) && (frontend->_gpsCheck & MASK_GPS_YAW_ERR)) {
  189. yawFail = true;
  190. } else {
  191. yawFail = false;
  192. }
  193. // Report check result as a text string and bitmask
  194. if (yawFail) {
  195. hal.util->snprintf(prearm_fail_string,
  196. sizeof(prearm_fail_string),
  197. "Mag yaw error x=%.1f y=%.1f",
  198. (double)magTestRatio.x,
  199. (double)magTestRatio.y);
  200. gpsCheckStatus.bad_yaw = true;
  201. } else {
  202. gpsCheckStatus.bad_yaw = false;
  203. }
  204. // assume failed first time through and notify user checks have started
  205. if (lastGpsVelFail_ms == 0) {
  206. hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "EKF starting GPS checks");
  207. lastGpsVelFail_ms = imuSampleTime_ms;
  208. }
  209. // record time of fail or pass
  210. if (gpsSpdAccFail || numSatsFail || hdopFail || hAccFail || vAccFail || yawFail || gpsDriftFail || gpsVertVelFail || gpsHorizVelFail) {
  211. lastGpsVelFail_ms = imuSampleTime_ms;
  212. } else {
  213. lastGpsVelPass_ms = imuSampleTime_ms;
  214. }
  215. // continuous period of 10s without fail required to set healthy
  216. // continuous period of 5s without pass required to set unhealthy
  217. if (!gpsGoodToAlign && imuSampleTime_ms - lastGpsVelFail_ms > 10000) {
  218. gpsGoodToAlign = true;
  219. } else if (gpsGoodToAlign && imuSampleTime_ms - lastGpsVelPass_ms > 5000) {
  220. gpsGoodToAlign = false;
  221. }
  222. }
  223. // update inflight calculaton that determines if GPS data is good enough for reliable navigation
  224. void NavEKF2_core::calcGpsGoodForFlight(void)
  225. {
  226. // use a simple criteria based on the GPS receivers claimed speed accuracy and the EKF innovation consistency checks
  227. // set up varaibles and constants used by filter that is applied to GPS speed accuracy
  228. const float alpha1 = 0.2f; // coefficient for first stage LPF applied to raw speed accuracy data
  229. const float tau = 10.0f; // time constant (sec) of peak hold decay
  230. if (lastGpsCheckTime_ms == 0) {
  231. lastGpsCheckTime_ms = imuSampleTime_ms;
  232. }
  233. float dtLPF = (imuSampleTime_ms - lastGpsCheckTime_ms) * 1e-3f;
  234. lastGpsCheckTime_ms = imuSampleTime_ms;
  235. float alpha2 = constrain_float(dtLPF/tau,0.0f,1.0f);
  236. // get the receivers reported speed accuracy
  237. float gpsSpdAccRaw;
  238. if (!AP::gps().speed_accuracy(gpsSpdAccRaw)) {
  239. gpsSpdAccRaw = 0.0f;
  240. }
  241. // filter the raw speed accuracy using a LPF
  242. sAccFilterState1 = constrain_float((alpha1 * gpsSpdAccRaw + (1.0f - alpha1) * sAccFilterState1),0.0f,10.0f);
  243. // apply a peak hold filter to the LPF output
  244. sAccFilterState2 = MAX(sAccFilterState1,((1.0f - alpha2) * sAccFilterState2));
  245. // Apply a threshold test with hysteresis to the filtered GPS speed accuracy data
  246. if (sAccFilterState2 > 1.5f ) {
  247. gpsSpdAccPass = false;
  248. } else if(sAccFilterState2 < 1.0f) {
  249. gpsSpdAccPass = true;
  250. }
  251. // Apply a threshold test with hysteresis to the normalised position and velocity innovations
  252. // Require a fail for one second and a pass for 10 seconds to transition
  253. if (lastInnovFailTime_ms == 0) {
  254. lastInnovFailTime_ms = imuSampleTime_ms;
  255. lastInnovPassTime_ms = imuSampleTime_ms;
  256. }
  257. if (velTestRatio < 1.0f && posTestRatio < 1.0f) {
  258. lastInnovPassTime_ms = imuSampleTime_ms;
  259. } else if (velTestRatio > 0.7f || posTestRatio > 0.7f) {
  260. lastInnovFailTime_ms = imuSampleTime_ms;
  261. }
  262. if ((imuSampleTime_ms - lastInnovPassTime_ms) > 1000) {
  263. ekfInnovationsPass = false;
  264. } else if ((imuSampleTime_ms - lastInnovFailTime_ms) > 10000) {
  265. ekfInnovationsPass = true;
  266. }
  267. // both GPS speed accuracy and EKF innovations must pass
  268. gpsAccuracyGood = gpsSpdAccPass && ekfInnovationsPass;
  269. }
  270. // Detect if we are in flight or on ground
  271. void NavEKF2_core::detectFlight()
  272. {
  273. /*
  274. If we are a fly forward type vehicle (eg plane), then in-air status can be determined through a combination of speed and height criteria.
  275. Because of the differing certainty requirements of algorithms that need the in-flight / on-ground status we use two booleans where
  276. onGround indicates a high certainty we are not flying and inFlight indicates a high certainty we are flying. It is possible for
  277. both onGround and inFlight to be false if the status is uncertain, but they cannot both be true.
  278. If we are a plane as indicated by the assume_zero_sideslip() status, then different logic is used
  279. TODO - this logic should be moved out of the EKF and into the flight vehicle code.
  280. */
  281. if (assume_zero_sideslip()) {
  282. // To be confident we are in the air we use a criteria which combines arm status, ground speed, airspeed and height change
  283. float gndSpdSq = sq(gpsDataDelayed.vel.x) + sq(gpsDataDelayed.vel.y);
  284. bool highGndSpd = false;
  285. bool highAirSpd = false;
  286. bool largeHgtChange = false;
  287. // trigger at 8 m/s airspeed
  288. if (_ahrs->airspeed_sensor_enabled()) {
  289. const AP_Airspeed *airspeed = _ahrs->get_airspeed();
  290. if (airspeed->get_airspeed() * AP::ahrs().get_EAS2TAS() > 10.0f) {
  291. highAirSpd = true;
  292. }
  293. }
  294. // trigger at 10 m/s GPS velocity, but not if GPS is reporting bad velocity errors
  295. if (gndSpdSq > 100.0f && gpsSpdAccuracy < 1.0f) {
  296. highGndSpd = true;
  297. }
  298. // trigger if more than 10m away from initial height
  299. if (fabsf(hgtMea) > 10.0f) {
  300. largeHgtChange = true;
  301. }
  302. // Determine to a high certainty we are flying
  303. if (motorsArmed && highGndSpd && (highAirSpd || largeHgtChange)) {
  304. onGround = false;
  305. inFlight = true;
  306. }
  307. // if is possible we are in flight, set the time this condition was last detected
  308. if (motorsArmed && (highGndSpd || highAirSpd || largeHgtChange)) {
  309. airborneDetectTime_ms = imuSampleTime_ms;
  310. onGround = false;
  311. }
  312. // Determine to a high certainty we are not flying
  313. // after 5 seconds of not detecting a possible flight condition or we are disarmed, we transition to on-ground mode
  314. if(!motorsArmed || ((imuSampleTime_ms - airborneDetectTime_ms) > 5000)) {
  315. onGround = true;
  316. inFlight = false;
  317. }
  318. } else {
  319. // Non fly forward vehicle, so can only use height and motor arm status
  320. // If the motors are armed then we could be flying and if they are not armed then we are definitely not flying
  321. if (motorsArmed) {
  322. onGround = false;
  323. } else {
  324. inFlight = false;
  325. onGround = true;
  326. }
  327. if (!onGround) {
  328. // If height has increased since exiting on-ground, then we definitely are flying
  329. if ((stateStruct.position.z - posDownAtTakeoff) < -1.5f) {
  330. inFlight = true;
  331. }
  332. // If rangefinder has increased since exiting on-ground, then we definitely are flying
  333. if ((rangeDataNew.rng - rngAtStartOfFlight) > 0.5f) {
  334. inFlight = true;
  335. }
  336. // If more than 5 seconds since likely_flying was set
  337. // true, then set inFlight true
  338. if (_ahrs->get_time_flying_ms() > 5000) {
  339. inFlight = true;
  340. }
  341. }
  342. }
  343. // store current on-ground and in-air status for next time
  344. prevOnGround = onGround;
  345. prevInFlight = inFlight;
  346. // Store vehicle height and range prior to takeoff for use in post takeoff checks
  347. if (onGround) {
  348. // store vertical position at start of flight to use as a reference for ground relative checks
  349. posDownAtTakeoff = stateStruct.position.z;
  350. // store the range finder measurement which will be used as a reference to detect when we have taken off
  351. rngAtStartOfFlight = rangeDataNew.rng;
  352. // if the magnetic field states have been set, then continue to update the vertical position
  353. // quaternion and yaw innovation snapshots to use as a reference when we start to fly.
  354. if (magStateInitComplete) {
  355. posDownAtLastMagReset = stateStruct.position.z;
  356. quatAtLastMagReset = stateStruct.quat;
  357. yawInnovAtLastMagReset = innovYaw;
  358. }
  359. }
  360. }
  361. // determine if a takeoff is expected so that we can compensate for expected barometer errors due to ground effect
  362. bool NavEKF2_core::getTakeoffExpected()
  363. {
  364. if (expectGndEffectTakeoff && imuSampleTime_ms - takeoffExpectedSet_ms > frontend->gndEffectTimeout_ms) {
  365. expectGndEffectTakeoff = false;
  366. }
  367. return expectGndEffectTakeoff;
  368. }
  369. // called by vehicle code to specify that a takeoff is happening
  370. // causes the EKF to compensate for expected barometer errors due to ground effect
  371. void NavEKF2_core::setTakeoffExpected(bool val)
  372. {
  373. takeoffExpectedSet_ms = imuSampleTime_ms;
  374. expectGndEffectTakeoff = val;
  375. }
  376. // determine if a touchdown is expected so that we can compensate for expected barometer errors due to ground effect
  377. bool NavEKF2_core::getTouchdownExpected()
  378. {
  379. if (expectGndEffectTouchdown && imuSampleTime_ms - touchdownExpectedSet_ms > frontend->gndEffectTimeout_ms) {
  380. expectGndEffectTouchdown = false;
  381. }
  382. return expectGndEffectTouchdown;
  383. }
  384. // called by vehicle code to specify that a touchdown is expected to happen
  385. // causes the EKF to compensate for expected barometer errors due to ground effect
  386. void NavEKF2_core::setTouchdownExpected(bool val)
  387. {
  388. touchdownExpectedSet_ms = imuSampleTime_ms;
  389. expectGndEffectTouchdown = val;
  390. }
  391. // Set to true if the terrain underneath is stable enough to be used as a height reference
  392. // in combination with a range finder. Set to false if the terrain underneath the vehicle
  393. // cannot be used as a height reference
  394. void NavEKF2_core::setTerrainHgtStable(bool val)
  395. {
  396. terrainHgtStableSet_ms = imuSampleTime_ms;
  397. terrainHgtStable = val;
  398. }
  399. // Detect takeoff for optical flow navigation
  400. void NavEKF2_core::detectOptFlowTakeoff(void)
  401. {
  402. if (!onGround && !takeOffDetected && (imuSampleTime_ms - timeAtArming_ms) > 1000) {
  403. // we are no longer confidently on the ground so check the range finder and gyro for signs of takeoff
  404. const AP_InertialSensor &ins = AP::ins();
  405. Vector3f angRateVec;
  406. Vector3f gyroBias;
  407. getGyroBias(gyroBias);
  408. bool dual_ins = ins.use_gyro(0) && ins.use_gyro(1);
  409. if (dual_ins) {
  410. angRateVec = (ins.get_gyro(0) + ins.get_gyro(1)) * 0.5f - gyroBias;
  411. } else {
  412. angRateVec = ins.get_gyro() - gyroBias;
  413. }
  414. takeOffDetected = (takeOffDetected || (angRateVec.length() > 0.1f) || (rangeDataNew.rng > (rngAtStartOfFlight + 0.1f)));
  415. } else if (onGround) {
  416. // we are confidently on the ground so set the takeoff detected status to false
  417. takeOffDetected = false;
  418. }
  419. }