Browse Source

Copter: gcs failsafe disabled by default

master
Randy Mackay 5 years ago
parent
commit
9b75da33fc
  1. 2
      ArduCopter/Parameters.cpp

2
ArduCopter/Parameters.cpp

@ -175,7 +175,7 @@ const AP_Param::Info Copter::var_info[] = { @@ -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

Loading…
Cancel
Save