Browse Source

Tracker: use AP_RTC

Tracker: AP_GPS now sets the system time directly
master
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
9f6d186bea
  1. 8
      AntennaTracker/sensors.cpp

8
AntennaTracker/sensors.cpp

@ -83,14 +83,6 @@ void Tracker::update_GPS(void) @@ -83,14 +83,6 @@ void Tracker::update_GPS(void)
current_loc = gps.location();
set_home(current_loc);
// 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) {
// Set compass declination automatically
compass.set_initial_location(gps.location().lat, gps.location().lng);

Loading…
Cancel
Save