AP_AdvancedFailsafe.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455
  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. AP_AdvancedFailsafe.cpp
  15. This is an advanced failsafe module originally modelled on the
  16. failsafe rules of the Outback Challenge
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include "AP_AdvancedFailsafe.h"
  20. #include <RC_Channel/RC_Channel.h>
  21. #include <SRV_Channel/SRV_Channel.h>
  22. #include <GCS_MAVLink/GCS.h>
  23. #include <AP_GPS/AP_GPS.h>
  24. #include <AP_Baro/AP_Baro.h>
  25. extern const AP_HAL::HAL& hal;
  26. // table of user settable parameters
  27. const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
  28. // @Param: ENABLE
  29. // @DisplayName: Enable Advanced Failsafe
  30. // @Description: This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
  31. // @User: Advanced
  32. AP_GROUPINFO_FLAGS("ENABLE", 11, AP_AdvancedFailsafe, _enable, 0, AP_PARAM_FLAG_ENABLE),
  33. // @Param: MAN_PIN
  34. // @DisplayName: Manual Pin
  35. // @Description: This sets a digital output pin to set high when in manual mode
  36. // @User: Advanced
  37. AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),
  38. // @Param: HB_PIN
  39. // @DisplayName: Heartbeat Pin
  40. // @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination.
  41. // @User: Advanced
  42. // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5
  43. AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),
  44. // @Param: WP_COMMS
  45. // @DisplayName: Comms Waypoint
  46. // @Description: Waypoint number to navigate to on comms loss
  47. // @User: Advanced
  48. AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),
  49. // @Param: GPS_LOSS
  50. // @DisplayName: GPS Loss Waypoint
  51. // @Description: Waypoint number to navigate to on GPS lock loss
  52. // @User: Advanced
  53. AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),
  54. // @Param: TERMINATE
  55. // @DisplayName: Force Terminate
  56. // @Description: Can be set in flight to force termination of the heartbeat signal
  57. // @User: Advanced
  58. AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),
  59. // @Param: TERM_ACTION
  60. // @DisplayName: Terminate action
  61. // @Description: This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup APM to handle it here. Please consult the wiki for more information on the possible values of the parameter
  62. // @User: Advanced
  63. AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),
  64. // @Param: TERM_PIN
  65. // @DisplayName: Terminate Pin
  66. // @Description: This sets a digital output pin to set high on flight termination
  67. // @User: Advanced
  68. // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5
  69. AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),
  70. // @Param: AMSL_LIMIT
  71. // @DisplayName: AMSL limit
  72. // @Description: This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
  73. // @User: Advanced
  74. // @Units: m
  75. AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),
  76. // @Param: AMSL_ERR_GPS
  77. // @DisplayName: Error margin for GPS based AMSL limit
  78. // @Description: This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
  79. // @User: Advanced
  80. // @Units: m
  81. AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),
  82. // @Param: QNH_PRESSURE
  83. // @DisplayName: QNH pressure
  84. // @Description: This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
  85. // @Units: mbar
  86. // @User: Advanced
  87. AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),
  88. // *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE
  89. // *NOTE* index 12 of AP_Int16 RC_FAIL_MS was depreciated. Replaced by RC_FAIL_TIME.
  90. // @Param: MAX_GPS_LOSS
  91. // @DisplayName: Maximum number of GPS loss events
  92. // @Description: Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
  93. // @User: Advanced
  94. AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),
  95. // @Param: MAX_COM_LOSS
  96. // @DisplayName: Maximum number of comms loss events
  97. // @Description: Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.
  98. // @User: Advanced
  99. AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),
  100. // @Param: GEOFENCE
  101. // @DisplayName: Enable geofence Advanced Failsafe
  102. // @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
  103. // @User: Advanced
  104. AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),
  105. // @Param: RC
  106. // @DisplayName: Enable RC Advanced Failsafe
  107. // @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
  108. // @User: Advanced
  109. AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),
  110. // @Param: RC_MAN_ONLY
  111. // @DisplayName: Enable RC Termination only in manual control modes
  112. // @Description: If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
  113. // @User: Advanced
  114. AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),
  115. // @Param: DUAL_LOSS
  116. // @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
  117. // @Description: This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.
  118. // @User: Advanced
  119. AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),
  120. // @Param: RC_FAIL_TIME
  121. // @DisplayName: RC failure time
  122. // @Description: This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
  123. // @User: Advanced
  124. // @Units: s
  125. AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),
  126. // @Param: MAX_RANGE
  127. // @DisplayName: Max allowed range
  128. // @Description: This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.
  129. // @User: Advanced
  130. // @Units: km
  131. AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0),
  132. AP_GROUPEND
  133. };
  134. // check for Failsafe conditions. This is called at 10Hz by the main
  135. // ArduPlane code
  136. void
  137. AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
  138. {
  139. if (!_enable) {
  140. return;
  141. }
  142. // we always check for fence breach
  143. if(_enable_geofence_fs) {
  144. if (geofence_breached || check_altlimit()) {
  145. if (!_terminate) {
  146. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");
  147. _terminate.set_and_notify(1);
  148. }
  149. }
  150. }
  151. // update max range check
  152. max_range_update();
  153. enum control_mode mode = afs_mode();
  154. // check if RC termination is enabled
  155. // check for RC failure in manual mode or RC failure when AFS_RC_MANUAL is 0
  156. if (_state != STATE_PREFLIGHT && !_terminate && _enable_RC_fs &&
  157. (mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) &&
  158. _rc_fail_time_seconds > 0 &&
  159. (AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) {
  160. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure");
  161. _terminate.set_and_notify(1);
  162. }
  163. // tell the failsafe board if we are in manual control
  164. // mode. This tells it to pass through controls from the
  165. // receiver
  166. if (_manual_pin != -1) {
  167. hal.gpio->pinMode(_manual_pin, HAL_GPIO_OUTPUT);
  168. hal.gpio->write(_manual_pin, mode==AFS_MANUAL);
  169. }
  170. uint32_t now = AP_HAL::millis();
  171. bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
  172. bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
  173. switch (_state) {
  174. case STATE_PREFLIGHT:
  175. // we startup in preflight mode. This mode ends when
  176. // we first enter auto.
  177. if (mode == AFS_AUTO) {
  178. gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO");
  179. _state = STATE_AUTO;
  180. }
  181. break;
  182. case STATE_AUTO:
  183. // this is the normal mode.
  184. if (!gcs_link_ok) {
  185. gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS");
  186. _state = STATE_DATA_LINK_LOSS;
  187. if (_wp_comms_hold) {
  188. _saved_wp = mission.get_current_nav_cmd().index;
  189. mission.set_current_cmd(_wp_comms_hold);
  190. }
  191. // if two events happen within 30s we consider it to be part of the same event
  192. if (now - _last_comms_loss_ms > 30*1000UL) {
  193. _comms_loss_count++;
  194. _last_comms_loss_ms = now;
  195. }
  196. break;
  197. }
  198. if (!gps_lock_ok) {
  199. gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS");
  200. _state = STATE_GPS_LOSS;
  201. if (_wp_gps_loss) {
  202. _saved_wp = mission.get_current_nav_cmd().index;
  203. mission.set_current_cmd(_wp_gps_loss);
  204. }
  205. // if two events happen within 30s we consider it to be part of the same event
  206. if (now - _last_gps_loss_ms > 30*1000UL) {
  207. _gps_loss_count++;
  208. _last_gps_loss_ms = now;
  209. }
  210. break;
  211. }
  212. break;
  213. case STATE_DATA_LINK_LOSS:
  214. if (!gps_lock_ok) {
  215. // losing GPS lock when data link is lost
  216. // leads to termination if AFS_DUAL_LOSS is 1
  217. if(_enable_dual_loss) {
  218. if (!_terminate) {
  219. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
  220. _terminate.set_and_notify(1);
  221. }
  222. }
  223. } else if (gcs_link_ok) {
  224. _state = STATE_AUTO;
  225. gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");
  226. // we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS
  227. if (_saved_wp != 0 &&
  228. (_max_comms_loss <= 0 ||
  229. _comms_loss_count <= _max_comms_loss)) {
  230. mission.set_current_cmd(_saved_wp);
  231. _saved_wp = 0;
  232. }
  233. }
  234. break;
  235. case STATE_GPS_LOSS:
  236. if (!gcs_link_ok) {
  237. // losing GCS link when GPS lock lost
  238. // leads to termination if AFS_DUAL_LOSS is 1
  239. if (!_terminate && _enable_dual_loss) {
  240. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
  241. _terminate.set_and_notify(1);
  242. }
  243. } else if (gps_lock_ok) {
  244. gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK");
  245. _state = STATE_AUTO;
  246. // we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS
  247. if (_saved_wp != 0 &&
  248. (_max_gps_loss <= 0 || _gps_loss_count <= _max_gps_loss)) {
  249. mission.set_current_cmd(_saved_wp);
  250. _saved_wp = 0;
  251. }
  252. }
  253. break;
  254. }
  255. // if we are not terminating or if there is a separate terminate
  256. // pin configured then toggle the heartbeat pin at 10Hz
  257. if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
  258. _heartbeat_pin_value = !_heartbeat_pin_value;
  259. hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);
  260. hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);
  261. }
  262. // set the terminate pin
  263. if (_terminate_pin != -1) {
  264. hal.gpio->pinMode(_terminate_pin, HAL_GPIO_OUTPUT);
  265. hal.gpio->write(_terminate_pin, _terminate?1:0);
  266. }
  267. }
  268. // send heartbeat messages during sensor calibration
  269. void
  270. AP_AdvancedFailsafe::heartbeat(void)
  271. {
  272. if (!_enable) {
  273. return;
  274. }
  275. // if we are not terminating or if there is a separate terminate
  276. // pin configured then toggle the heartbeat pin at 10Hz
  277. if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
  278. _heartbeat_pin_value = !_heartbeat_pin_value;
  279. hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);
  280. hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);
  281. }
  282. }
  283. // check for altitude limit breach
  284. bool
  285. AP_AdvancedFailsafe::check_altlimit(void)
  286. {
  287. if (!_enable) {
  288. return false;
  289. }
  290. if (_amsl_limit == 0 || _qnh_pressure <= 0) {
  291. // no limit set
  292. return false;
  293. }
  294. // see if the barometer is dead
  295. const AP_Baro &baro = AP::baro();
  296. const AP_GPS &gps = AP::gps();
  297. if (AP_HAL::millis() - baro.get_last_update() > 5000) {
  298. // the barometer has been unresponsive for 5 seconds. See if we can switch to GPS
  299. if (_amsl_margin_gps != -1 &&
  300. gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
  301. gps.location().alt*0.01f <= _amsl_limit - _amsl_margin_gps) {
  302. // GPS based altitude OK
  303. return false;
  304. }
  305. // no barometer - immediate termination
  306. return true;
  307. }
  308. float alt_amsl = baro.get_altitude_difference(_qnh_pressure*100, baro.get_pressure());
  309. if (alt_amsl > _amsl_limit) {
  310. // pressure altitude breach
  311. return true;
  312. }
  313. // all OK
  314. return false;
  315. }
  316. /*
  317. return true if we should crash the vehicle
  318. */
  319. bool AP_AdvancedFailsafe::should_crash_vehicle(void)
  320. {
  321. if (!_enable) {
  322. return false;
  323. }
  324. // ensure failsafe values are setup for if FMU crashes on PX4/Pixhawk
  325. if (!_failsafe_setup) {
  326. _failsafe_setup = true;
  327. setup_IO_failsafe();
  328. }
  329. // determine if the vehicle should be crashed
  330. // only possible if FS_TERM_ACTION is 42 and _terminate is non zero
  331. // _terminate may be set via parameters, or a mavlink command
  332. if (_terminate &&
  333. (_terminate_action == TERMINATE_ACTION_TERMINATE ||
  334. _terminate_action == TERMINATE_ACTION_LAND)) {
  335. // we are terminating
  336. return true;
  337. }
  338. // continue flying
  339. return false;
  340. }
  341. // update GCS based termination
  342. // returns true if AFS is in the desired termination state
  343. bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {
  344. if (!_enable) {
  345. gcs().send_text(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");
  346. return false;
  347. }
  348. _terminate.set_and_notify(should_terminate ? 1 : 0);
  349. // evaluate if we will crash or not, as AFS must be enabled, and TERM_ACTION has to be correct
  350. bool is_terminating = should_crash_vehicle();
  351. if(should_terminate == is_terminating) {
  352. if (is_terminating) {
  353. gcs().send_text(MAV_SEVERITY_INFO, "Terminating due to %s", reason);
  354. } else {
  355. gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);
  356. }
  357. return true;
  358. } else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
  359. gcs().send_text(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");
  360. }
  361. return false;
  362. }
  363. /*
  364. update check of maximum range
  365. */
  366. void AP_AdvancedFailsafe::max_range_update(void)
  367. {
  368. if (_max_range_km <= 0) {
  369. return;
  370. }
  371. if (!_have_first_location) {
  372. if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
  373. // wait for 3D fix
  374. return;
  375. }
  376. if (!hal.util->get_soft_armed()) {
  377. // wait for arming
  378. return;
  379. }
  380. _first_location = AP::gps().location();
  381. _have_first_location = true;
  382. }
  383. if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
  384. // don't trigger when dead-reckoning
  385. return;
  386. }
  387. // check distance from first location
  388. float distance_km = _first_location.get_distance(AP::gps().location()) * 0.001;
  389. if (distance_km > _max_range_km) {
  390. uint32_t now = AP_HAL::millis();
  391. if (now - _term_range_notice_ms > 5000) {
  392. gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km);
  393. _term_range_notice_ms = now;
  394. }
  395. _terminate.set_and_notify(1);
  396. }
  397. }