Sub: ensure that gcs and crash failsafes always happen

This commit is contained in:
jaxxzer 2016-02-20 22:39:48 -05:00 committed by Andrew Tridgell
parent 1d0ddcc270
commit 94c7de36e1
2 changed files with 4 additions and 4 deletions

View File

@ -15,7 +15,7 @@ void Sub::crash_check()
static uint16_t crash_counter; // number of iterations vehicle may have been crashed static uint16_t crash_counter; // number of iterations vehicle may have been crashed
// return immediately if disarmed, or crash checking disabled // return immediately if disarmed, or crash checking disabled
if (!motors.armed() || ap.land_complete || g.fs_crash_check == 0) { if (!motors.armed() || g.fs_crash_check == 0) {
crash_counter = 0; crash_counter = 0;
return; return;
} }

View File

@ -171,13 +171,13 @@ void Sub::failsafe_gcs_check()
// return immediately if gcs failsafe is disabled, gcs has never been connected or we are not overriding rc controls from the gcs and we are not in guided mode // return immediately if gcs failsafe is disabled, gcs has never been connected or we are not overriding rc controls from the gcs and we are not in guided mode
// this also checks to see if we have a GCS failsafe active, if we do, then must continue to process the logic for recovery from this state. // this also checks to see if we have a GCS failsafe active, if we do, then must continue to process the logic for recovery from this state.
if ((!failsafe.gcs) && (g.failsafe_gcs == FS_GCS_DISABLED || failsafe.last_heartbeat_ms == 0 || (!failsafe.rc_override_active && control_mode != GUIDED))) { if ((!failsafe.gcs) && (g.failsafe_gcs == FS_GCS_DISABLED)) {
return; return;
} }
// calc time since last gcs update // calc time since last gcs update
// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs // note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
last_gcs_update_ms = millis() - failsafe.last_heartbeat_ms; last_gcs_update_ms = AP_HAL::millis() - failsafe.last_heartbeat_ms;
// check if all is well // check if all is well
if (last_gcs_update_ms < FS_GCS_TIMEOUT_MS) { if (last_gcs_update_ms < FS_GCS_TIMEOUT_MS) {