mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: Ensure update_GPS does nothing when gps is disabled.
This fixes a bug in which an APM without a GPS would not work because it would constantly scan for a valid GPS long after it should have given up and moved on.
This commit is contained in:
parent
5c9dc00ae2
commit
72d76558a7
|
@ -1331,6 +1331,11 @@ static void update_GPS(void)
|
||||||
// A counter that is used to grab at least 10 reads before commiting the Home location
|
// A counter that is used to grab at least 10 reads before commiting the Home location
|
||||||
static byte ground_start_count = 10;
|
static byte ground_start_count = 10;
|
||||||
|
|
||||||
|
// return immediately if GPS is not enabled
|
||||||
|
if( !GPS_enabled ) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
g_gps->update();
|
g_gps->update();
|
||||||
update_GPS_light();
|
update_GPS_light();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue