mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: reduce WPNAV_LOIT_MINA parameter description range
This commit is contained in:
parent
7d0cac15fb
commit
2dc111ff39
@ -92,7 +92,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = {
|
|||||||
// @DisplayName: Loiter minimum acceleration
|
// @DisplayName: Loiter minimum acceleration
|
||||||
// @Description: Loiter minimum acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered, but cause a larger jerk when the copter stops.
|
// @Description: Loiter minimum acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered, but cause a larger jerk when the copter stops.
|
||||||
// @Units: cm/s/s
|
// @Units: cm/s/s
|
||||||
// @Range: 100 981
|
// @Range: 25 250
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("LOIT_MINA", 9, AC_WPNav, _loiter_accel_min_cmss, WPNAV_LOITER_ACCEL_MIN),
|
AP_GROUPINFO("LOIT_MINA", 9, AC_WPNav, _loiter_accel_min_cmss, WPNAV_LOITER_ACCEL_MIN),
|
||||||
|
Loading…
Reference in New Issue
Block a user