AP_GPS: make time_epoch_usec const

This commit is contained in:
Peter Barker 2017-07-26 12:47:00 +10:00 committed by Francisco Ferreira
parent db7c8439c6
commit 7f59279670
2 changed files with 3 additions and 3 deletions

View File

@ -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) {

View File

@ -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);
}