From 7b3af5863444b8cbf44ff0bab419590837be2c8f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 28 Feb 2017 15:33:59 +0900 Subject: [PATCH] AC_Avoidance: fix AVOID_ANGLE_MAX parameter description --- libraries/AC_Avoidance/AC_Avoid.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 13831f1d3b..13ba965970 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -10,7 +10,7 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { // @User: Standard AP_GROUPINFO("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_ALL), - // @Param: ANGLE MAX + // @Param: ANGLE_MAX // @DisplayName: Avoidance max lean angle in non-GPS flight modes // @Description: Max lean angle used to avoid obstacles while in non-GPS modes // @Range: 0 4500