mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: remove unused ap.gps_status flag
This commit is contained in:
parent
2c48c20088
commit
0f8f5bc048
@ -127,13 +127,3 @@ void set_compass_healthy(bool b)
|
|||||||
}
|
}
|
||||||
ap.compass_status = b;
|
ap.compass_status = b;
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_gps_healthy(bool b)
|
|
||||||
{
|
|
||||||
if(ap.gps_status != b){
|
|
||||||
if(false == b){
|
|
||||||
Log_Write_Event(DATA_LOST_GPS);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
ap.gps_status = b;
|
|
||||||
}
|
|
||||||
|
@ -1337,8 +1337,6 @@ static void update_GPS(void)
|
|||||||
g_gps->update();
|
g_gps->update();
|
||||||
update_GPS_light();
|
update_GPS_light();
|
||||||
|
|
||||||
set_gps_healthy(g_gps->status() >= GPS::GPS_OK_FIX_3D);
|
|
||||||
|
|
||||||
if (g_gps->new_data && last_gps_time != g_gps->time && g_gps->status() >= GPS::GPS_OK_FIX_2D) {
|
if (g_gps->new_data && last_gps_time != g_gps->time && g_gps->status() >= GPS::GPS_OK_FIX_2D) {
|
||||||
// clear new data flag
|
// clear new data flag
|
||||||
g_gps->new_data = false;
|
g_gps->new_data = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user