diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index f36cbe9dd6..72f9dc5c68 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -519,7 +519,7 @@ uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const uint64_t fix_time_ms; // add in the time since the last fix message if (istate.last_corrected_gps_time_us != 0) { - fix_time_ms = time_epoch_convert(istate.time_week, drivers[instance]->get_last_itow()); + fix_time_ms = time_epoch_convert(istate.time_week, drivers[instance]->get_last_itow_ms()); return (fix_time_ms*1000ULL) + (AP_HAL::micros64() - istate.last_corrected_gps_time_us); } else { fix_time_ms = time_epoch_convert(istate.time_week, istate.time_week_ms); @@ -536,7 +536,7 @@ uint64_t AP_GPS::last_message_epoch_usec(uint8_t instance) const if (istate.time_week == 0) { return 0; } - return time_epoch_convert(istate.time_week, drivers[instance]->get_last_itow()) * 1000ULL; + return time_epoch_convert(istate.time_week, drivers[instance]->get_last_itow_ms()) * 1000ULL; } /* @@ -2020,7 +2020,7 @@ uint32_t AP_GPS::get_itow(uint8_t instance) const if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) { return 0; } - return drivers[instance]->get_last_itow(); + return drivers[instance]->get_last_itow_ms(); } bool AP_GPS::get_error_codes(uint8_t instance, uint32_t &error_codes) const diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index 7581c8ef33..eab22b3e50 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -124,7 +124,7 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg) state.last_corrected_gps_time_us = (corrected_ms * 1000ULL); state.corrected_timestamp_updated = true; if (state.last_corrected_gps_time_us) { - _last_itow = state.time_week_ms; + _last_itow_ms = state.time_week_ms; } if (have_yaw) { state.gps_yaw_time_ms = corrected_ms; diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp index ea57ca9ccd..ddb6205bf6 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp @@ -880,7 +880,7 @@ bool AP_GPS_UAVCAN::read(void) // If we were able to get a valid last_corrected_gps_time_us // we have had a valid GPS message time, from which we calculate // the time of week. - _last_itow = interim_state.time_week_ms; + _last_itow_ms = interim_state.time_week_ms; } return true; } diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index ea09008b94..e47ff483f2 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -235,8 +235,8 @@ void AP_GPS_Backend::set_uart_timestamp(uint16_t nbytes) void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length) { - if (itow != _last_itow) { - _last_itow = itow; + if (itow != _last_itow_ms) { + _last_itow_ms = itow; /* we need to calculate a pseudo-itow, which copes with the diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index d0d5cda68f..937542f249 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -94,8 +94,8 @@ public: virtual bool get_error_codes(uint32_t &error_codes) const { return false; } // return iTOW of last message, or zero if not supported - uint32_t get_last_itow(void) const { - return (_pseudo_itow_delta_ms == 0)?(_last_itow):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms); + uint32_t get_last_itow_ms(void) const { + return (_pseudo_itow_delta_ms == 0)?(_last_itow_ms):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms); } enum DriverOptions : int16_t { @@ -112,7 +112,7 @@ protected: uint64_t _last_pps_time_us; JitterCorrection jitter_correction; - uint32_t _last_itow; + uint32_t _last_itow_ms; // common utility functions int32_t swap_int32(int32_t v) const;