mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
Plane: raise range of THR_FS_VALUE
need to cope with reversed throttle
This commit is contained in:
parent
e0a9a8196c
commit
b7fe96188d
@ -597,7 +597,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Param: THR_FS_VALUE
|
||||
// @DisplayName: Throttle Failsafe Value
|
||||
// @Description: The PWM level on channel 3 below which throttle failsafe triggers
|
||||
// @Range: 925 1100
|
||||
// @Range: 925 2200
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE", THROTTLE_FS_VALUE),
|
||||
|
Loading…
Reference in New Issue
Block a user