AP_PrecLand: correct metatdata for YAW_ALIGN

This commit is contained in:
Hwurzburg 2021-05-20 08:23:39 -05:00 committed by Randy Mackay
parent e46969957a
commit a2f1c6e19e
1 changed files with 2 additions and 2 deletions

View File

@ -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),