mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_GPS: set _last_itow alongside state.last_corrected_gps_time_us
This commit is contained in:
parent
e77bb74f9b
commit
d3d3c826f7
@ -123,6 +123,9 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg)
|
|||||||
uint32_t corrected_ms = jitter.correct_offboard_timestamp_msec(timestamp_ms, now_ms);
|
uint32_t corrected_ms = jitter.correct_offboard_timestamp_msec(timestamp_ms, now_ms);
|
||||||
state.last_corrected_gps_time_us = (corrected_ms * 1000ULL);
|
state.last_corrected_gps_time_us = (corrected_ms * 1000ULL);
|
||||||
state.corrected_timestamp_updated = true;
|
state.corrected_timestamp_updated = true;
|
||||||
|
if (state.last_corrected_gps_time_us) {
|
||||||
|
_last_itow = state.time_week_ms;
|
||||||
|
}
|
||||||
if (have_yaw) {
|
if (have_yaw) {
|
||||||
state.gps_yaw_time_ms = corrected_ms;
|
state.gps_yaw_time_ms = corrected_ms;
|
||||||
}
|
}
|
||||||
|
@ -876,7 +876,12 @@ bool AP_GPS_UAVCAN::read(void)
|
|||||||
interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0);
|
interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0);
|
||||||
|
|
||||||
state = interim_state;
|
state = interim_state;
|
||||||
|
if (interim_state.last_corrected_gps_time_us) {
|
||||||
|
// 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;
|
||||||
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (!seen_message) {
|
if (!seen_message) {
|
||||||
|
@ -95,7 +95,7 @@ public:
|
|||||||
|
|
||||||
// return iTOW of last message, or zero if not supported
|
// return iTOW of last message, or zero if not supported
|
||||||
uint32_t get_last_itow(void) const {
|
uint32_t get_last_itow(void) const {
|
||||||
return (_pseudo_itow_delta_ms == 0)?(_last_itow*1000ULL):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms);
|
return (_pseudo_itow_delta_ms == 0)?(_last_itow):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms);
|
||||||
}
|
}
|
||||||
|
|
||||||
enum DriverOptions : int16_t {
|
enum DriverOptions : int16_t {
|
||||||
@ -110,6 +110,10 @@ protected:
|
|||||||
AP_GPS &gps; ///< access to frontend (for parameters)
|
AP_GPS &gps; ///< access to frontend (for parameters)
|
||||||
AP_GPS::GPS_State &state; ///< public state for this instance
|
AP_GPS::GPS_State &state; ///< public state for this instance
|
||||||
|
|
||||||
|
uint64_t _last_pps_time_us;
|
||||||
|
JitterCorrection jitter_correction;
|
||||||
|
uint32_t _last_itow;
|
||||||
|
|
||||||
// common utility functions
|
// common utility functions
|
||||||
int32_t swap_int32(int32_t v) const;
|
int32_t swap_int32(int32_t v) const;
|
||||||
int16_t swap_int16(int16_t v) const;
|
int16_t swap_int16(int16_t v) const;
|
||||||
@ -161,13 +165,8 @@ protected:
|
|||||||
void log_data(const uint8_t *data, uint16_t length);
|
void log_data(const uint8_t *data, uint16_t length);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
protected:
|
|
||||||
uint64_t _last_pps_time_us;
|
|
||||||
JitterCorrection jitter_correction;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// itow from previous message
|
// itow from previous message
|
||||||
uint32_t _last_itow;
|
|
||||||
uint64_t _pseudo_itow;
|
uint64_t _pseudo_itow;
|
||||||
int32_t _pseudo_itow_delta_ms;
|
int32_t _pseudo_itow_delta_ms;
|
||||||
uint32_t _last_ms;
|
uint32_t _last_ms;
|
||||||
|
Loading…
Reference in New Issue
Block a user