mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Sub: disarm motors if failsafe action fails
This commit is contained in:
parent
4fe8746a2a
commit
4fae5cdfcf
@ -346,9 +346,13 @@ void Sub::failsafe_gcs_check()
|
|||||||
if (g.failsafe_gcs == FS_GCS_DISARM) {
|
if (g.failsafe_gcs == FS_GCS_DISARM) {
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
} else if (g.failsafe_gcs == FS_GCS_HOLD && motors.armed()) {
|
} 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()) {
|
} 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();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user