diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 695e139772..65716e057f 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -117,7 +117,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: LEARN // @DisplayName: Learn compass offsets automatically // @Description: Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes. - // @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning,3:InFlight-Learning + // @Values: 0:Disabled,2:EKF-Learning,3:InFlight-Learning // @User: Advanced AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT), #endif diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 75e8e46984..6a10ba3a97 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -320,7 +320,7 @@ public: enum LearnType { LEARN_NONE=0, - LEARN_INTERNAL=1, + // LEARN_INTERNAL=1, LEARN_EKF=2, LEARN_INFLIGHT=3 };