mirror of https://github.com/ArduPilot/ardupilot
AP_PrecLand: correct metatdata for YAW_ALIGN
This commit is contained in:
parent
e46969957a
commit
a2f1c6e19e
|
@ -30,8 +30,8 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
|
|||
// @Param: YAW_ALIGN
|
||||
// @DisplayName: Sensor yaw alignment
|
||||
// @Description: Yaw angle from body x-axis to sensor x-axis.
|
||||
// @Range: 0 360
|
||||
// @Increment: 1
|
||||
// @Range: 0 36000
|
||||
// @Increment: 10
|
||||
// @User: Advanced
|
||||
// @Units: cdeg
|
||||
AP_GROUPINFO("YAW_ALIGN", 2, AC_PrecLand, _yaw_align, 0),
|
||||
|
|
Loading…
Reference in New Issue