From ed999a283fb87ec0ad8411978e0f5a765abe847d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Apr 2016 18:51:06 +1000 Subject: [PATCH] AP_Compass: added get_learn_type() API this allows caller to determine if EKF offsets should be saved --- libraries/AP_Compass/AP_Compass.cpp | 8 ++++---- libraries/AP_Compass/AP_Compass.h | 11 +++++++++++ 2 files changed, 15 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 4cac8d4bd3..145ece1fff 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -15,9 +15,9 @@ extern AP_HAL::HAL& hal; #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) -#define COMPASS_LEARN_DEFAULT 0 +#define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE #else -#define COMPASS_LEARN_DEFAULT 1 +#define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL #endif const AP_Param::GroupInfo Compass::var_info[] = { @@ -56,8 +56,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: LEARN // @DisplayName: Learn compass offsets automatically - // @Description: Enable or disable the automatic learning of compass offsets - // @Values: 0:Disabled,1:Enabled + // @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. + // @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning // @User: Advanced AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT), diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index aafdf0040b..2ca525cafe 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -294,6 +294,17 @@ public: Vector3f field[COMPASS_MAX_INSTANCES]; } _hil; + enum LearnType { + LEARN_NONE=0, + LEARN_INTERNAL=1, + LEARN_EKF=2 + }; + + // return the chosen learning type + enum LearnType get_learn_type(void) const { + return (enum LearnType)_learn.get(); + } + private: /// Register a new compas driver, allocating an instance number ///