mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Copter: enable radio failsafe by default
This commit is contained in:
parent
7ea0f65590
commit
1a246851fc
@ -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
|
// @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
|
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always LAND
|
||||||
// @User: Standard
|
// @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
|
// @Param: FS_THR_VALUE
|
||||||
// @DisplayName: Throttle Failsafe Value
|
// @DisplayName: Throttle Failsafe Value
|
||||||
|
Loading…
Reference in New Issue
Block a user