mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
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:
parent
7a7e44ae3c
commit
c45c02ce82
@ -397,7 +397,7 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state,
|
|||||||
goto bad_yaw;
|
goto bad_yaw;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef HAL_BUILD_AP_PERIPH
|
#if AP_AHRS_ENABLED
|
||||||
{
|
{
|
||||||
// get lag
|
// get lag
|
||||||
float lag = 0.1;
|
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;
|
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
|
// at this point the offsets are looking okay, go ahead and actually calculate a useful heading
|
||||||
|
Loading…
Reference in New Issue
Block a user