mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: correct param ranges to accomodate TradHeli defaults
This commit is contained in:
parent
3f4d4e45fc
commit
158c7c499d
|
@ -28,7 +28,7 @@ const AP_Param::GroupInfo AC_Loiter::var_info[] = {
|
|||
// @DisplayName: Loiter Horizontal Maximum Speed
|
||||
// @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
|
||||
// @Units: cm/s
|
||||
// @Range: 20 2000
|
||||
// @Range: 20 3500
|
||||
// @Increment: 50
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED", 2, AC_Loiter, _speed_cms, LOITER_SPEED_DEFAULT),
|
||||
|
|
Loading…
Reference in New Issue