From ba5db0c5d82a9e28cb79bcbc38fcc31e2ffe421c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 14 Sep 2016 09:57:52 +0900 Subject: [PATCH] Compass: add CAL_FIT parameter description values No functional change --- libraries/AP_Compass/AP_Compass.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 55be015a79..00e045f3fd 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -356,7 +356,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: CAL_FIT // @DisplayName: Compass calibration fitness // @Description: This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value. - // @Range: 4 20 + // @Range: 4 32 + // @Values: 4:Very Strict,8:Default,16:Relaxed,32:Very Relaxed // @Increment: 0.1 // @User: Advanced AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, 8.0f),