123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_AdvancedFailsafe.h"
- #include <RC_Channel/RC_Channel.h>
- #include <SRV_Channel/SRV_Channel.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Baro/AP_Baro.h>
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
-
-
-
-
- AP_GROUPINFO_FLAGS("ENABLE", 11, AP_AdvancedFailsafe, _enable, 0, AP_PARAM_FLAG_ENABLE),
-
-
-
-
- AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),
-
-
-
-
-
- AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),
-
-
-
-
- AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),
-
-
-
-
- AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),
-
-
-
-
- AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),
-
-
-
-
- AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),
-
-
-
-
-
- AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),
-
-
-
-
-
- AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),
-
-
-
-
-
- AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),
-
-
-
-
-
- AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),
-
-
-
-
-
-
- AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),
-
-
-
-
- AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),
-
-
-
-
- AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),
-
-
-
-
- AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),
-
-
-
-
- AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),
-
-
-
-
- AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),
-
-
-
-
-
- AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),
-
-
-
-
-
- AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0),
-
- AP_GROUPEND
- };
- void
- AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
- {
- if (!_enable) {
- return;
- }
-
- if(_enable_geofence_fs) {
- if (geofence_breached || check_altlimit()) {
- if (!_terminate) {
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");
- _terminate.set_and_notify(1);
- }
- }
- }
-
- max_range_update();
- enum control_mode mode = afs_mode();
-
-
-
- if (_state != STATE_PREFLIGHT && !_terminate && _enable_RC_fs &&
- (mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) &&
- _rc_fail_time_seconds > 0 &&
- (AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) {
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure");
- _terminate.set_and_notify(1);
- }
-
-
-
-
- if (_manual_pin != -1) {
- hal.gpio->pinMode(_manual_pin, HAL_GPIO_OUTPUT);
- hal.gpio->write(_manual_pin, mode==AFS_MANUAL);
- }
- uint32_t now = AP_HAL::millis();
- bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
- bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
- switch (_state) {
- case STATE_PREFLIGHT:
-
-
- if (mode == AFS_AUTO) {
- gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO");
- _state = STATE_AUTO;
- }
- break;
- case STATE_AUTO:
-
- if (!gcs_link_ok) {
- gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS");
- _state = STATE_DATA_LINK_LOSS;
- if (_wp_comms_hold) {
- _saved_wp = mission.get_current_nav_cmd().index;
- mission.set_current_cmd(_wp_comms_hold);
- }
-
- if (now - _last_comms_loss_ms > 30*1000UL) {
- _comms_loss_count++;
- _last_comms_loss_ms = now;
- }
- break;
- }
- if (!gps_lock_ok) {
- gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS");
- _state = STATE_GPS_LOSS;
- if (_wp_gps_loss) {
- _saved_wp = mission.get_current_nav_cmd().index;
- mission.set_current_cmd(_wp_gps_loss);
- }
-
- if (now - _last_gps_loss_ms > 30*1000UL) {
- _gps_loss_count++;
- _last_gps_loss_ms = now;
- }
- break;
- }
- break;
- case STATE_DATA_LINK_LOSS:
- if (!gps_lock_ok) {
-
-
- if(_enable_dual_loss) {
- if (!_terminate) {
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
- _terminate.set_and_notify(1);
- }
- }
- } else if (gcs_link_ok) {
- _state = STATE_AUTO;
- gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");
-
- if (_saved_wp != 0 &&
- (_max_comms_loss <= 0 ||
- _comms_loss_count <= _max_comms_loss)) {
- mission.set_current_cmd(_saved_wp);
- _saved_wp = 0;
- }
- }
- break;
- case STATE_GPS_LOSS:
- if (!gcs_link_ok) {
-
-
- if (!_terminate && _enable_dual_loss) {
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
- _terminate.set_and_notify(1);
- }
- } else if (gps_lock_ok) {
- gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK");
- _state = STATE_AUTO;
-
- if (_saved_wp != 0 &&
- (_max_gps_loss <= 0 || _gps_loss_count <= _max_gps_loss)) {
- mission.set_current_cmd(_saved_wp);
- _saved_wp = 0;
- }
- }
- break;
- }
-
-
- if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
- _heartbeat_pin_value = !_heartbeat_pin_value;
- hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);
- hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);
- }
-
- if (_terminate_pin != -1) {
- hal.gpio->pinMode(_terminate_pin, HAL_GPIO_OUTPUT);
- hal.gpio->write(_terminate_pin, _terminate?1:0);
- }
- }
- void
- AP_AdvancedFailsafe::heartbeat(void)
- {
- if (!_enable) {
- return;
- }
-
-
- if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
- _heartbeat_pin_value = !_heartbeat_pin_value;
- hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);
- hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);
- }
- }
- bool
- AP_AdvancedFailsafe::check_altlimit(void)
- {
- if (!_enable) {
- return false;
- }
- if (_amsl_limit == 0 || _qnh_pressure <= 0) {
-
- return false;
- }
-
- const AP_Baro &baro = AP::baro();
- const AP_GPS &gps = AP::gps();
- if (AP_HAL::millis() - baro.get_last_update() > 5000) {
-
- if (_amsl_margin_gps != -1 &&
- gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
- gps.location().alt*0.01f <= _amsl_limit - _amsl_margin_gps) {
-
- return false;
- }
-
- return true;
- }
- float alt_amsl = baro.get_altitude_difference(_qnh_pressure*100, baro.get_pressure());
- if (alt_amsl > _amsl_limit) {
-
- return true;
- }
-
-
- return false;
- }
- bool AP_AdvancedFailsafe::should_crash_vehicle(void)
- {
- if (!_enable) {
- return false;
- }
-
- if (!_failsafe_setup) {
- _failsafe_setup = true;
- setup_IO_failsafe();
- }
-
-
-
- if (_terminate &&
- (_terminate_action == TERMINATE_ACTION_TERMINATE ||
- _terminate_action == TERMINATE_ACTION_LAND)) {
-
- return true;
- }
-
- return false;
- }
- bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {
- if (!_enable) {
- gcs().send_text(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");
- return false;
- }
- _terminate.set_and_notify(should_terminate ? 1 : 0);
-
- bool is_terminating = should_crash_vehicle();
- if(should_terminate == is_terminating) {
- if (is_terminating) {
- gcs().send_text(MAV_SEVERITY_INFO, "Terminating due to %s", reason);
- } else {
- gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);
- }
- return true;
- } else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
- gcs().send_text(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");
- }
- return false;
- }
- void AP_AdvancedFailsafe::max_range_update(void)
- {
- if (_max_range_km <= 0) {
- return;
- }
- if (!_have_first_location) {
- if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
-
- return;
- }
- if (!hal.util->get_soft_armed()) {
-
- return;
- }
- _first_location = AP::gps().location();
- _have_first_location = true;
- }
- if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
-
- return;
- }
-
-
- float distance_km = _first_location.get_distance(AP::gps().location()) * 0.001;
- if (distance_km > _max_range_km) {
- uint32_t now = AP_HAL::millis();
- if (now - _term_range_notice_ms > 5000) {
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km);
- _term_range_notice_ms = now;
- }
- _terminate.set_and_notify(1);
- }
- }
|