From c870df0351f1bf2399be7f9bffe8ec4349943a6c Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Mon, 6 Jan 2020 23:06:54 +0000 Subject: [PATCH] AP_Compass: get_time_flying in vehicle --- libraries/AP_Compass/Compass_learn.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index 9498b17fb6..8e8f028ee8 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -9,6 +9,7 @@ #include #include +#include #if COMPASS_LEARN_ENABLED @@ -33,14 +34,15 @@ CompassLearn::CompassLearn(Compass &_compass) : */ void CompassLearn::update(void) { - const AP_AHRS &ahrs = AP::ahrs(); + const AP_Vehicle *vehicle = AP::vehicle(); if (converged || compass.get_learn_type() != Compass::LEARN_INFLIGHT || - !hal.util->get_soft_armed() || ahrs.get_time_flying_ms() < 3000) { + !hal.util->get_soft_armed() || vehicle->get_time_flying_ms() < 3000) { // only learn when flying and with enough time to be clear of // the ground return; } + const AP_AHRS &ahrs = AP::ahrs(); if (!have_earth_field) { Location loc; if (!ahrs.get_position(loc)) {