AP_GPS: use AP_AHRS_ENABLED in place of HAL_BUILD_AP_PERIPH

the guard here is just against use of the singleton
This commit is contained in:
Peter Barker 2021-11-23 16:37:18 +11:00 committed by Andrew Tridgell
parent 7a7e44ae3c
commit c45c02ce82

View File

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