mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Rover: set system time on GPS lock
This commit is contained in:
parent
b897285737
commit
c8e21c194d
@ -832,6 +832,10 @@ static void update_GPS(void)
|
||||
|
||||
} else {
|
||||
init_home();
|
||||
|
||||
// set system clock for log timestamps
|
||||
hal.util->set_system_clock(g_gps->time_epoch_usec());
|
||||
|
||||
if (g.compass_enabled) {
|
||||
// Set compass declination automatically
|
||||
compass.set_initial_location(g_gps->latitude, g_gps->longitude);
|
||||
|
Loading…
Reference in New Issue
Block a user