From a2f1c6e19ea58c25123dcb544158674fd4aadd82 Mon Sep 17 00:00:00 2001 From: Hwurzburg Date: Thu, 20 May 2021 08:23:39 -0500 Subject: [PATCH] AP_PrecLand: correct metatdata for YAW_ALIGN --- libraries/AC_PrecLand/AC_PrecLand.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index c842615ad0..ebc4851174 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -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),