From 421fbef2a0a459643f6fe7482b34a3c23fbc53db Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 Nov 2019 09:45:02 +1100 Subject: [PATCH] AP_Compass: added COMPASS_OPTIONS this allows user to set that calibration requires GPS lock --- libraries/AP_Compass/AP_Compass.cpp | 9 ++++++++- libraries/AP_Compass/AP_Compass.h | 6 ++++++ libraries/AP_Compass/AP_Compass_Calibration.cpp | 7 +++++++ 3 files changed, 21 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 2b471a7032..c87c8fdb79 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -533,7 +533,14 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Range: 0 1.3 AP_GROUPINFO("SCALE3", 42, Compass, _state[2].scale_factor, 0), #endif - + + // @Param: OPTIONS + // @DisplayName: Compass options + // @Description: This sets options to change the behaviour of the compass + // @Bitmask: 0:CalRequireGPS + // @User: Advanced + AP_GROUPINFO("OPTIONS", 43, Compass, _options, 0), + AP_GROUPEND }; diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 8d2218b316..61f3a2c7c1 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -472,6 +472,12 @@ private: AP_Int16 _offset_max; + // bitmask of options + enum class Option : uint16_t { + CAL_REQUIRE_GPS = (1U<<0), + }; + AP_Int16 _options; + #if COMPASS_CAL_ENABLED CompassCalibrator _calibrator[COMPASS_MAX_INSTANCES]; #endif diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index add1babc62..fcd7f318ce 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -1,5 +1,6 @@ #include #include +#include #include #include "AP_Compass.h" @@ -54,6 +55,12 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) if (!use_for_yaw(i)) { return false; } + if (_options.get() & uint16_t(Option::CAL_REQUIRE_GPS)) { + if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) { + gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock"); + return false; + } + } if (!is_calibrating()) { AP_Notify::events.initiated_compass_cal = 1; }