From 9b269b1b5612ddb9dd4acf774aeb15b770dca4cd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 9 Mar 2018 13:14:05 -0300 Subject: [PATCH] Rover: use AP_RTC Rover: AP_GPS now sets the system time directly --- APMrover2/APMrover2.cpp | 2 -- APMrover2/Rover.h | 4 ---- APMrover2/commands.cpp | 22 ---------------------- 3 files changed, 28 deletions(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index fa9dbd3797..b887ab39fe 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -306,8 +306,6 @@ void Rover::update_GPS(void) if (gps.last_message_time_ms() != last_gps_msg_ms) { last_gps_msg_ms = gps.last_message_time_ms(); - // set system time if necessary - set_system_time_from_GPS(); #if CAMERA == ENABLED camera.update(); #endif diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index f94b27d843..b5f323802b 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -317,9 +317,6 @@ private: // The home location used for RTL. The location is set when we first get stable GPS lock const struct Location &home; - // true if the system time has been set from the GPS - bool system_time_set; - // true if the compass's initial location has been set bool compass_init_location; @@ -427,7 +424,6 @@ private: void update_home_from_EKF(); bool set_home_to_current_location(bool lock); bool set_home(const Location& loc, bool lock); - void set_system_time_from_GPS(); void update_home(); // compat.cpp diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 1dc31abbb4..43056083d9 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -86,28 +86,6 @@ bool Rover::set_home(const Location& loc, bool lock) return true; } -// checks if we should update ahrs/RTL home position from GPS -void Rover::set_system_time_from_GPS() -{ - // exit immediately if system time already set - if (system_time_set) { - return; - } - - // if we have a 3d lock and valid location - if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) { - // set system clock for log timestamps - const 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); - - system_time_set = true; - } -} - /* update home location from GPS this is called as long as we have 3D lock and the arming switch is