Rover: use AP_RTC

Rover: AP_GPS now sets the system time directly
This commit is contained in:
Peter Barker 2018-03-09 13:14:05 -03:00 committed by Andrew Tridgell
parent 5b41db5120
commit 9b269b1b56
3 changed files with 0 additions and 28 deletions

View File

@ -306,8 +306,6 @@ void Rover::update_GPS(void)
if (gps.last_message_time_ms() != last_gps_msg_ms) { if (gps.last_message_time_ms() != last_gps_msg_ms) {
last_gps_msg_ms = gps.last_message_time_ms(); last_gps_msg_ms = gps.last_message_time_ms();
// set system time if necessary
set_system_time_from_GPS();
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera.update(); camera.update();
#endif #endif

View File

@ -317,9 +317,6 @@ private:
// The home location used for RTL. The location is set when we first get stable GPS lock // The home location used for RTL. The location is set when we first get stable GPS lock
const struct Location &home; 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 // true if the compass's initial location has been set
bool compass_init_location; bool compass_init_location;
@ -427,7 +424,6 @@ private:
void update_home_from_EKF(); void update_home_from_EKF();
bool set_home_to_current_location(bool lock); bool set_home_to_current_location(bool lock);
bool set_home(const Location& loc, bool lock); bool set_home(const Location& loc, bool lock);
void set_system_time_from_GPS();
void update_home(); void update_home();
// compat.cpp // compat.cpp

View File

@ -86,28 +86,6 @@ bool Rover::set_home(const Location& loc, bool lock)
return true; 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 update home location from GPS
this is called as long as we have 3D lock and the arming switch is this is called as long as we have 3D lock and the arming switch is