mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 19:03:58 -04:00
Plane: use AP_RTC
Plane: AP_GPS now sets the system time directly
This commit is contained in:
parent
9f6d186bea
commit
9824832523
@ -440,14 +440,6 @@ void Plane::update_GPS_10Hz(void)
|
|||||||
|
|
||||||
next_WP_loc = prev_WP_loc = home;
|
next_WP_loc = prev_WP_loc = home;
|
||||||
|
|
||||||
// set system clock for log timestamps
|
|
||||||
uint64_t gps_timestamp = gps.time_epoch_usec();
|
|
||||||
|
|
||||||
hal.util->set_system_clock(gps_timestamp);
|
|
||||||
|
|
||||||
// update signing timestamp
|
|
||||||
GCS_MAVLINK::update_signing_timestamp(gps_timestamp);
|
|
||||||
|
|
||||||
if (g.compass_enabled) {
|
if (g.compass_enabled) {
|
||||||
// Set compass declination automatically
|
// Set compass declination automatically
|
||||||
const Location &loc = gps.location();
|
const Location &loc = gps.location();
|
||||||
|
Loading…
Reference in New Issue
Block a user