ArduCopter: update signing timestamp on GPS lock
This commit is contained in:
parent
b8fa1bc9f7
commit
57870cccb9
@ -136,7 +136,13 @@ void Copter::set_system_time_from_GPS()
|
|||||||
// if we have a 3d lock and valid location
|
// if we have a 3d lock and valid location
|
||||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
// set system clock for log timestamps
|
// set system clock for log timestamps
|
||||||
hal.util->set_system_clock(gps.time_epoch_usec());
|
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);
|
||||||
|
|
||||||
ap.system_time_set = true;
|
ap.system_time_set = true;
|
||||||
Log_Write_Event(DATA_SYSTEM_TIME_SET);
|
Log_Write_Event(DATA_SYSTEM_TIME_SET);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user