AP_Compass: added get_learn_type() API

this allows caller to determine if EKF offsets should be saved
This commit is contained in:
Andrew Tridgell 2016-04-28 18:51:06 +10:00
parent ebe552bdc5
commit ed999a283f
2 changed files with 15 additions and 4 deletions

View File

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

View File

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