mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: pre-arm check of FS_GCS_ENABLE=2
This commit is contained in:
parent
42b85c88ed
commit
e1aaea0834
@ -159,6 +159,10 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
||||
return false;
|
||||
}
|
||||
}
|
||||
if (copter.g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {
|
||||
// FS_GCS_ENABLE == 2 has been removed
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "FS_GCS_ENABLE=2 removed, see FS_OPTIONS");
|
||||
}
|
||||
|
||||
// lean angle parameter check
|
||||
if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {
|
||||
|
Loading…
Reference in New Issue
Block a user