mirror of https://github.com/ArduPilot/ardupilot
AP_RTC: added a millisecond jitter correction function
This commit is contained in:
parent
cc4db3e458
commit
f1d32df783
|
@ -87,3 +87,14 @@ uint64_t JitterCorrection::correct_offboard_timestamp_usec(uint64_t offboard_use
|
|||
|
||||
return uint64_t(estimate_us);
|
||||
}
|
||||
|
||||
/*
|
||||
correct an offboard timestamp in microseconds into a local
|
||||
timestamp, removing timing jitter caused by the transport.
|
||||
|
||||
Return a value in milliseconds since boot in the local time domain
|
||||
*/
|
||||
uint32_t JitterCorrection::correct_offboard_timestamp_msec(uint32_t offboard_ms, uint32_t local_ms)
|
||||
{
|
||||
return correct_offboard_timestamp_usec(offboard_ms*1000ULL, local_ms*1000ULL) / 1000ULL;
|
||||
}
|
||||
|
|
|
@ -13,6 +13,10 @@ public:
|
|||
// timestamp. See JitterCorrection.cpp for details
|
||||
uint64_t correct_offboard_timestamp_usec(uint64_t offboard_usec, uint64_t local_usec);
|
||||
|
||||
// correct an offboard timestamp to a jitter-free local
|
||||
// timestamp. See JitterCorrection.cpp for details
|
||||
uint32_t correct_offboard_timestamp_msec(uint32_t offboard_ms, uint32_t local_ms);
|
||||
|
||||
private:
|
||||
const uint16_t max_lag_ms;
|
||||
const uint16_t convergence_loops;
|
||||
|
|
Loading…
Reference in New Issue