From c45c02ce828402fd378e548b19812ccb9f1e1e81 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 23 Nov 2021 16:37:18 +1100 Subject: [PATCH] AP_GPS: use AP_AHRS_ENABLED in place of HAL_BUILD_AP_PERIPH the guard here is just against use of the singleton --- libraries/AP_GPS/GPS_Backend.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 89cff87262..3b442cffc8 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -397,7 +397,7 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, goto bad_yaw; } -#ifndef HAL_BUILD_AP_PERIPH +#if AP_AHRS_ENABLED { // get lag float lag = 0.1; @@ -425,7 +425,7 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, goto bad_yaw; } } -#endif // HAL_BUILD_AP_PERIPH +#endif // AP_AHRS_ENABLED { // at this point the offsets are looking okay, go ahead and actually calculate a useful heading