mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: work around scheduling issue in example code
This commit is contained in:
parent
e40e50e2e1
commit
30f5e2c37f
|
@ -12,6 +12,7 @@
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
#include <AP_HAL_AVR_SITL.h>
|
#include <AP_HAL_AVR_SITL.h>
|
||||||
#include <AP_HAL_PX4.h>
|
#include <AP_HAL_PX4.h>
|
||||||
|
#include <AP_HAL_Linux.h>
|
||||||
#include <AP_HAL_Empty.h>
|
#include <AP_HAL_Empty.h>
|
||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
#include <DataFlash.h>
|
#include <DataFlash.h>
|
||||||
|
@ -70,6 +71,7 @@ void loop()
|
||||||
gps.time_week_ms(),
|
gps.time_week_ms(),
|
||||||
gps.status());
|
gps.status());
|
||||||
}
|
}
|
||||||
|
hal.scheduler->delay(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
|
Loading…
Reference in New Issue