AC_Avoidance: fix AVOID_ANGLE_MAX parameter description

This commit is contained in:
Randy Mackay 2017-02-28 15:33:59 +09:00
parent eb746eaeef
commit 7b3af58634

View File

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