mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Terrain: use GPS singleton
This commit is contained in:
parent
fb3cba3867
commit
ca4f25a78e
@ -47,7 +47,7 @@ void AP_Terrain::update_mission_data(void)
|
||||
|
||||
uint16_t pending, loaded;
|
||||
get_statistics(pending, loaded);
|
||||
if (pending && ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (pending && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
// wait till we have fully filled the current set of grids
|
||||
return;
|
||||
}
|
||||
@ -124,7 +124,7 @@ void AP_Terrain::update_rally_data(void)
|
||||
|
||||
uint16_t pending, loaded;
|
||||
get_statistics(pending, loaded);
|
||||
if (pending && ahrs.get_gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (pending && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
// wait till we have fully filled the current set of grids
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user