diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 47c273740a..8c7d7402c4 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -283,7 +283,7 @@ const AP_Param::Info Copter::var_info[] = { // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always LAND // @User: Standard - GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_DISABLED), + GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL), // @Param: FS_THR_VALUE // @DisplayName: Throttle Failsafe Value