diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index e93cafdadc..1e8d0cc854 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -49,7 +49,7 @@ void CompassLearn::update(void) const AP_AHRS &ahrs = AP::ahrs(); if (!have_earth_field) { Location loc; - if (!ahrs.get_position(loc)) { + if (!ahrs.get_position(loc) && !ahrs.get_origin(loc)) { // need to wait till we have a global position return; }