mirror of https://github.com/ArduPilot/ardupilot
Plane: set system time on GPS lock
This commit is contained in:
parent
6b2222c32e
commit
b897285737
|
@ -1027,6 +1027,9 @@ static void update_GPS(void)
|
||||||
} else {
|
} else {
|
||||||
init_home();
|
init_home();
|
||||||
|
|
||||||
|
// set system clock for log timestamps
|
||||||
|
hal.util->set_system_clock(g_gps->time_epoch_usec());
|
||||||
|
|
||||||
if (g.compass_enabled) {
|
if (g.compass_enabled) {
|
||||||
// Set compass declination automatically
|
// Set compass declination automatically
|
||||||
compass.set_initial_location(g_gps->latitude, g_gps->longitude);
|
compass.set_initial_location(g_gps->latitude, g_gps->longitude);
|
||||||
|
|
Loading…
Reference in New Issue