mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: remove unnecessary multiply with 1000ULL in time_epoch_usec
This commit is contained in:
parent
5cb1444b1d
commit
e77bb74f9b
@ -522,7 +522,7 @@ uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const
|
|||||||
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());
|
||||||
return (fix_time_ms*1000ULL) + (AP_HAL::micros64() - istate.last_corrected_gps_time_us);
|
return (fix_time_ms*1000ULL) + (AP_HAL::micros64() - istate.last_corrected_gps_time_us);
|
||||||
} else {
|
} else {
|
||||||
fix_time_ms = time_epoch_convert(istate.time_week, istate.time_week_ms) * 1000ULL;
|
fix_time_ms = time_epoch_convert(istate.time_week, istate.time_week_ms);
|
||||||
return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;
|
return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user