103 void handle_message(
const mavlink_message_t *
msg);
109 uint64_t sync_stamp(uint64_t usec);
122 void add_sample(int64_t offset_us);
128 bool sync_converged();
137 uint32_t _sequence{0};
140 double _time_offset{0};
141 double _time_skew{0};
148 uint32_t _high_deviation_count{0};
149 uint32_t _high_rtt_count{0};
static constexpr uint32_t MAX_CONSECUTIVE_HIGH_DEVIATION
static constexpr double BETA_GAIN_FINAL
High-resolution timer with callouts and timekeeping.
static constexpr double BETA_GAIN_INITIAL
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
static constexpr uint32_t CONVERGENCE_WINDOW
static constexpr double ALPHA_GAIN_FINAL
static constexpr uint64_t MAX_RTT_SAMPLE
static constexpr uint64_t MAX_DEVIATION_SAMPLE
static constexpr uint32_t MAX_CONSECUTIVE_HIGH_RTT
static constexpr double ALPHA_GAIN_INITIAL
static constexpr time_t PX4_EPOCH_SECS