From 7f592796707aae52cdc26904f96f8b5796f92c0a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 26 Jul 2017 12:47:00 +1000 Subject: [PATCH] AP_GPS: make time_epoch_usec const --- libraries/AP_GPS/AP_GPS.cpp | 2 +- libraries/AP_GPS/AP_GPS.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 7c26ed2184..79c45f69f3 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -346,7 +346,7 @@ uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms) /** calculate current time since the unix epoch in microseconds */ -uint64_t AP_GPS::time_epoch_usec(uint8_t instance) +uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const { const GPS_State &istate = state[instance]; if (istate.last_gps_time_ms == 0) { diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index c82f801865..8dc45b478a 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -373,8 +373,8 @@ public: void send_blob_update(uint8_t instance); // return last fix time since the 1/1/1970 in microseconds - uint64_t time_epoch_usec(uint8_t instance); - uint64_t time_epoch_usec(void) { + uint64_t time_epoch_usec(uint8_t instance) const; + uint64_t time_epoch_usec(void) const { return time_epoch_usec(primary_instance); }