AP_NavEKF3_VehicleStatus.cpp 20 KB

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