From e7d73aa8566abaffefefddcc0f13af636b692777 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 9 Apr 2014 10:50:35 +0900 Subject: [PATCH] Copter: enable GCS failsafe to RTL by default This only triggers if the user has been using the GCS's RC override --- ArduCopter/Parameters.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index def1ca2924..6deec059fa 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -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