Copter: enable GCS failsafe to RTL by default
This only triggers if the user has been using the GCS's RC override
This commit is contained in:
parent
037a0b4e5a
commit
e7d73aa856
@ -143,7 +143,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds
|
||||
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode
|
||||
// @User: Standard
|
||||
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),
|
||||
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_ENABLED_ALWAYS_RTL),
|
||||
|
||||
// @Param: GPS_HDOP_GOOD
|
||||
// @DisplayName: GPS Hdop Good
|
||||
|
Loading…
Reference in New Issue
Block a user