Sub: disarm motors if failsafe action fails

This commit is contained in:
Jacob Walser 2018-04-21 00:35:03 -04:00
parent 4fe8746a2a
commit 4fae5cdfcf

View File

@ -346,9 +346,13 @@ void Sub::failsafe_gcs_check()
if (g.failsafe_gcs == FS_GCS_DISARM) {
init_disarm_motors();
} else if (g.failsafe_gcs == FS_GCS_HOLD && motors.armed()) {
set_mode(ALT_HOLD, MODE_REASON_GCS_FAILSAFE);
if (!set_mode(ALT_HOLD, MODE_REASON_GCS_FAILSAFE)) {
init_disarm_motors();
}
} else if (g.failsafe_gcs == FS_GCS_SURFACE && motors.armed()) {
set_mode(SURFACE, MODE_REASON_GCS_FAILSAFE);
if (!set_mode(SURFACE, MODE_REASON_GCS_FAILSAFE)) {
init_disarm_motors();
}
}
}