Skip to content
Snippets Groups Projects
Commit e7d73aa8 authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter: enable GCS failsafe to RTL by default

This only triggers if the user has been using the GCS's RC override
parent 037a0b4e
No related branches found
No related tags found
No related merge requests found
...@@ -143,7 +143,7 @@ const AP_Param::Info var_info[] PROGMEM = { ...@@ -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 // @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 // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode
// @User: Standard // @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 // @Param: GPS_HDOP_GOOD
// @DisplayName: GPS Hdop Good // @DisplayName: GPS Hdop Good
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment