From 9b75da33fcfb2e33ba11710e3366b18af1e17813 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 23 Dec 2019 13:39:08 +0900 Subject: [PATCH] Copter: gcs failsafe disabled by default --- ArduCopter/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 009a25c516..3d38e3ab2e 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -175,7 +175,7 @@ const AP_Param::Info Copter::var_info[] = { // @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. NB. The GCS Failsafe is only active when RC_OVERRIDE is being used to control the vehicle. // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Deprecated in 4.0+),3:Enabled always SmartRTL or RTL,4:Enabled always SmartRTL or Land,5:Enabled always land (4.0+ Only) // @User: Standard - GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_ENABLED_ALWAYS_RTL), + GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED), // @Param: GPS_HDOP_GOOD // @DisplayName: GPS Hdop Good