AP_Compass: allow learning with origin only

This commit is contained in:
Willian Galvani 2024-01-25 14:02:39 -03:00
parent d58884ee08
commit 1c98e2063c
1 changed files with 1 additions and 1 deletions

View File

@ -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;
}