mirror of https://github.com/ArduPilot/ardupilot
APM: fixed loiter radius docs to reflect new limit
This commit is contained in:
parent
276b26fa67
commit
110a2b8af6
|
@ -185,7 +185,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||||
// @DisplayName: Waypoint Loiter Radius
|
// @DisplayName: Waypoint Loiter Radius
|
||||||
// @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter
|
// @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter
|
||||||
// @Units: Meters
|
// @Units: Meters
|
||||||
// @Range: 1 127
|
// @Range: 1 32767
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
|
GSCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
|
||||||
|
|
Loading…
Reference in New Issue