From fc9eb797bee2bc716fe170b764d068816440a533 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Wed, 5 Apr 2017 17:14:31 -0400 Subject: [PATCH] Sub: Fix redundant call --- ArduSub/commands.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduSub/commands.cpp b/ArduSub/commands.cpp index 3ad25be0d4..a6a3ce66d9 100644 --- a/ArduSub/commands.cpp +++ b/ArduSub/commands.cpp @@ -141,10 +141,9 @@ void Sub::set_system_time_from_GPS() // if we have a 3d lock and valid location if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) { - // set system clock for log timestamps - hal.util->set_system_clock(gps.time_epoch_usec()); uint64_t gps_timestamp = gps.time_epoch_usec(); + // set system clock for log timestamps hal.util->set_system_clock(gps_timestamp); // update signing timestamp