19 #include <sensor_msgs/TimeReference.h> 20 #include <std_msgs/Duration.h> 21 #include <mavros_msgs/TimesyncStatus.h> 24 namespace std_plugins {
51 std::lock_guard<std::mutex> lock(
mutex);
66 void tick(int64_t rtt_ns, uint64_t remote_timestamp_ns, int64_t time_offset_ns)
68 std::lock_guard<std::mutex> lock(
mutex);
79 std::lock_guard<std::mutex> lock(
mutex);
85 std::lock_guard<std::mutex> lock(
mutex);
91 double freq = events / window;
97 stat.
summary(2,
"No events recorded.");
100 stat.
summary(1,
"Frequency too low.");
103 stat.
summary(1,
"Frequency too high.");
109 stat.
addf(
"Timesyncs since startup",
"%d",
count_);
110 stat.
addf(
"Frequency (Hz)",
"%f", freq);
114 stat.
addf(
"Estimated time offset (s)",
"%0.9f",
offset / 1e9);
141 dt_diag(
"Time Sync", 10),
148 high_deviation_count(0)
155 PluginBase::initialize(uas_);
157 double conn_system_time_d;
158 double conn_timesync_d;
159 std::string ts_mode_str;
164 if (nh.getParam(
"conn/system_time_rate", conn_system_time_d) && conn_system_time_d != 0.0) {
168 if (nh.getParam(
"conn/timesync_rate", conn_timesync_d) && conn_timesync_d != 0.0) {
172 nh.param<std::string>(
"time/time_ref_source", time_ref_source,
"fcu");
173 nh.param<std::string>(
"time/timesync_mode", ts_mode_str,
"MAVLINK");
185 nh.param(
"time/timesync_alpha_initial", filter_alpha_initial, 0.05
f);
186 nh.param(
"time/timesync_beta_initial", filter_beta_initial, 0.05
f);
187 nh.param(
"time/timesync_alpha_final", filter_alpha_final, 0.003
f);
188 nh.param(
"time/timesync_beta_final", filter_beta_final, 0.003
f);
189 filter_alpha = filter_alpha_initial;
190 filter_beta = filter_beta_initial;
198 nh.param(
"time/convergence_window", convergence_window, 500);
209 nh.param(
"time/max_rtt_sample", max_rtt_sample, 10);
210 nh.param(
"time/max_deviation_sample", max_deviation_sample, 100);
211 nh.param(
"time/max_consecutive_high_rtt", max_cons_high_rtt, 5);
212 nh.param(
"time/max_consecutive_high_deviation", max_cons_high_deviation, 5);
216 m_uas->set_timesync_mode(ts_mode);
219 time_ref_pub = nh.advertise<sensor_msgs::TimeReference>(
"time_reference", 10);
221 timesync_status_pub = nh.advertise<mavros_msgs::TimesyncStatus>(
"timesync_status", 10);
224 if (!conn_system_time.
isZero()) {
225 sys_time_timer = nh.createTimer(conn_system_time,
227 sys_time_timer.start();
231 if (!conn_timesync.
isZero() && !(ts_mode == TSM::NONE || ts_mode == TSM::PASSTHROUGH)) {
235 timesync_timer = nh.createTimer(conn_timesync,
237 timesync_timer.start();
285 void handle_system_time(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYSTEM_TIME &mtime)
288 const bool fcu_time_valid = mtime.time_unix_usec > 1234567890ULL * 1000000;
290 if (fcu_time_valid) {
292 auto time_unix = boost::make_shared<sensor_msgs::TimeReference>();
294 mtime.time_unix_usec / 1000000,
295 (mtime.time_unix_usec % 1000000) * 1000);
298 time_unix->time_ref = time_ref;
299 time_unix->source = time_ref_source;
301 time_ref_pub.
publish(time_unix);
308 void handle_timesync(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::TIMESYNC &tsync)
312 if (tsync.tc1 == 0) {
313 send_timesync_msg(now_ns, tsync.ts1);
316 else if (tsync.tc1 > 0) {
319 add_timesync_observation((tsync.ts1 + now_ns - tsync.tc1 * 2) / 2, tsync.ts1, tsync.tc1);
328 mavlink::common::msg::SYSTEM_TIME
mtime {};
329 mtime.time_unix_usec = time_unix_usec;
336 auto ts_mode = m_uas->get_timesync_mode();
337 if (ts_mode == TSM::MAVLINK) {
339 }
else if (ts_mode == TSM::ONBOARD) {
342 uint64_t monotonic_now_ns = get_monotonic_now();
344 add_timesync_observation(realtime_now_ns - monotonic_now_ns, realtime_now_ns, monotonic_now_ns);
350 mavlink::common::msg::TIMESYNC tsync {};
354 UAS_FCU(m_uas)->send_message_ignore_drop(tsync);
362 uint64_t rtt_ns = now_ns - local_time_ns;
365 uint64_t deviation = llabs(int64_t(time_offset) - offset_ns);
367 if (rtt_ns < max_rtt_sample * 1000000ULL) {
368 if (sync_converged() && (deviation > max_deviation_sample * 1000000ULL)) {
370 high_deviation_count++;
374 if (high_deviation_count > max_cons_high_deviation) {
375 ROS_ERROR_NAMED(
"time",
"TM : Time jump detected. Resetting time synchroniser.");
386 if (!sync_converged()) {
388 float progress =
float(sequence) / convergence_window;
389 float p = 1.0f - expf(0.5
f * (1.0
f - 1.0
f / (1.0
f - progress)));
390 filter_alpha = p * filter_alpha_final + (1.0f - p) * filter_alpha_initial;
391 filter_beta = p * filter_beta_final + (1.0f - p) * filter_beta_initial;
393 filter_alpha = filter_alpha_final;
394 filter_beta = filter_beta_final;
398 add_sample(offset_ns);
401 m_uas->set_time_offset(sync_converged() ? time_offset : 0);
407 high_deviation_count = 0;
416 if (high_rtt_count > max_cons_high_rtt) {
418 ROS_WARN_NAMED(
"time",
"TM : RTT too high for timesync: %0.2f ms.", rtt_ns / 1000000.0);
426 auto timesync_status = boost::make_shared<mavros_msgs::TimesyncStatus>();
429 timesync_status->remote_timestamp_ns = remote_time_ns;
430 timesync_status->observed_offset_ns = offset_ns;
431 timesync_status->estimated_offset_ns = time_offset;
432 timesync_status->round_trip_time_ms =
float(rtt_ns / 1000000.0);
434 timesync_status_pub.
publish(timesync_status);
437 dt_diag.
tick(rtt_ns, remote_time_ns, time_offset);
447 double time_offset_prev = time_offset;
450 time_offset = offset_ns;
453 time_offset = filter_alpha * offset_ns + (1.0 - filter_alpha) * (time_offset + time_skew);
456 time_skew = filter_beta * (time_offset - time_offset_prev) + (1.0 - filter_beta) * time_skew;
466 filter_alpha = filter_alpha_initial;
467 filter_beta = filter_beta_initial;
468 high_deviation_count = 0;
474 return sequence >= convergence_window;
479 struct timespec spec;
480 clock_gettime(CLOCK_MONOTONIC, &spec);
482 return spec.tv_sec * 1000000000ULL + spec.tv_nsec;
void timesync_cb(const ros::TimerEvent &event)
ros::Timer timesync_timer
MAVROS Plugin base class.
uint64_t get_monotonic_now(void)
int max_cons_high_deviation
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
utils::timesync_mode timesync_mode
void summary(unsigned char lvl, const std::string s)
std::vector< ros::Time > times_
float filter_beta_initial
void add_sample(int64_t offset_ns)
ros::Publisher time_ref_pub
std::string time_ref_source
#define UAS_DIAG(uasobjptr)
helper accessor to diagnostic updater
#define ROS_INFO_STREAM_NAMED(name, args)
void set_timestamp(uint64_t remote_timestamp_ns)
void addf(const std::string &key, const char *format,...)
void send_timesync_msg(uint64_t tc1, uint64_t ts1)
void sys_time_cb(const ros::TimerEvent &event)
std::vector< int > seq_nums_
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
std::string to_string(timesync_mode e)
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
const size_t window_size_
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
DiagnosticTask(const std::string name)
timesync_mode timesync_mode_from_str(const std::string &mode)
Retrieve timesync mode from name.
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
void add_timesync_observation(int64_t offset_ns, uint64_t local_time_ns, uint64_t remote_time_ns)
void tick(int64_t rtt_ns, uint64_t remote_timestamp_ns, int64_t time_offset_ns)
void initialize(UAS &uas_)
Plugin initializer.
#define ROS_ERROR_NAMED(name,...)
ros::Publisher timesync_status_pub
float filter_alpha_initial
void handle_timesync(const mavlink::mavlink_message_t *msg, mavlink::common::msg::TIMESYNC &tsync)
void handle_system_time(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYSTEM_TIME &mtime)
TimeSyncStatus(const std::string &name, size_t win_size)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::recursive_mutex mutex
ros::Timer sys_time_timer