mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: fix units metadata for PTCH_LIM_MIN_DEG
This commit is contained in:
parent
75978f9d6f
commit
17a17a5955
@ -533,7 +533,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Param: PTCH_LIM_MIN_DEG
|
||||
// @DisplayName: Minimum Pitch Angle
|
||||
// @Description: Maximum pitch down angle commanded in modes with stabilized limits
|
||||
// @Units: cdeg
|
||||
// @Units: deg
|
||||
// @Range: -90 0
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
|
Loading…
Reference in New Issue
Block a user