PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_timesync.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file mavlink_timesync.cpp
36  * Mavlink timesync implementation.
37  *
38  * @author Mohammed Kabir <mhkabir98@gmail.com>
39  */
40 
41 #include "mavlink_timesync.h"
42 #include "mavlink_main.h"
43 
44 #include <stdlib.h>
45 
47  _mavlink(mavlink)
48 {
49 }
50 
51 void
52 MavlinkTimesync::handle_message(const mavlink_message_t *msg)
53 {
54  switch (msg->msgid) {
55  case MAVLINK_MSG_ID_TIMESYNC: {
56 
57  mavlink_timesync_t tsync = {};
58  mavlink_msg_timesync_decode(msg, &tsync);
59 
60  const uint64_t now = hrt_absolute_time();
61 
62  if (tsync.tc1 == 0) { // Message originating from remote system, timestamp and return it
63 
64  mavlink_timesync_t rsync;
65 
66  rsync.tc1 = now * 1000ULL;
67  rsync.ts1 = tsync.ts1;
68 
69  mavlink_msg_timesync_send_struct(_mavlink->get_channel(), &rsync);
70 
71  return;
72 
73  } else if (tsync.tc1 > 0) { // Message originating from this system, compute time offset from it
74 
75  // Calculate time offset between this system and the remote system, assuming RTT for
76  // the timesync packet is roughly equal both ways.
77  int64_t offset_us = (int64_t)((tsync.ts1 / 1000ULL) + now - (tsync.tc1 / 1000ULL) * 2) / 2 ;
78 
79  // Calculate the round trip time (RTT) it took the timesync packet to bounce back to us from remote system
80  uint64_t rtt_us = now - (tsync.ts1 / 1000ULL);
81 
82  // Calculate the difference of this sample from the current estimate
83  uint64_t deviation = llabs((int64_t)_time_offset - offset_us);
84 
85  if (rtt_us < MAX_RTT_SAMPLE) { // Only use samples with low RTT
86 
87  if (sync_converged() && (deviation > MAX_DEVIATION_SAMPLE)) {
88 
89  // Increment the counter if we have a good estimate and are getting samples far from the estimate
91 
92  // We reset the filter if we received 5 consecutive samples which violate our present estimate.
93  // This is most likely due to a time jump on the offboard system.
95  PX4_ERR("[timesync] Time jump detected. Resetting time synchroniser.");
96  // Reset the filter
97  reset_filter();
98  }
99 
100  } else {
101 
102  // Filter gain scheduling
103  if (!sync_converged()) {
104  // Interpolate with a sigmoid function
105  double progress = (double)_sequence / (double)CONVERGENCE_WINDOW;
106  double p = 1.0 - exp(0.5 * (1.0 - 1.0 / (1.0 - progress)));
108  _filter_beta = p * BETA_GAIN_FINAL + (1.0 - p) * BETA_GAIN_INITIAL;
109 
110  } else {
113  }
114 
115  // Perform filter update
116  add_sample(offset_us);
117 
118  // Increment sequence counter after filter update
119  _sequence++;
120 
121  // Reset high deviation count after filter update
123 
124  // Reset high RTT count after filter update
125  _high_rtt_count = 0;
126  }
127 
128  } else {
129  // Increment counter if round trip time is too high for accurate timesync
130  _high_rtt_count++;
131 
133  PX4_WARN("[timesync] RTT too high for timesync: %llu ms", rtt_us / 1000ULL);
134  // Reset counter to rate-limit warnings
135  _high_rtt_count = 0;
136  }
137 
138  }
139 
140  // Publish status message
141  timesync_status_s tsync_status{};
142 
143  tsync_status.timestamp = hrt_absolute_time();
144  tsync_status.remote_timestamp = tsync.tc1 / 1000ULL;
145  tsync_status.observed_offset = offset_us;
146  tsync_status.estimated_offset = (int64_t)_time_offset;
147  tsync_status.round_trip_time = rtt_us;
148 
149  _timesync_status_pub.publish(tsync_status);
150  }
151 
152  break;
153  }
154 
155  case MAVLINK_MSG_ID_SYSTEM_TIME: {
156 
157  mavlink_system_time_t time;
158  mavlink_msg_system_time_decode(msg, &time);
159 
160  timespec tv = {};
161  px4_clock_gettime(CLOCK_REALTIME, &tv);
162 
163  // date -d @1234567890: Sat Feb 14 02:31:30 MSK 2009
164  bool onb_unix_valid = (unsigned long long)tv.tv_sec > PX4_EPOCH_SECS;
165  bool ofb_unix_valid = time.time_unix_usec > PX4_EPOCH_SECS * 1000ULL;
166 
167  if (!onb_unix_valid && ofb_unix_valid) {
168  tv.tv_sec = time.time_unix_usec / 1000000ULL;
169  tv.tv_nsec = (time.time_unix_usec % 1000000ULL) * 1000ULL;
170 
171  if (px4_clock_settime(CLOCK_REALTIME, &tv)) {
172  PX4_ERR("[timesync] Failed setting realtime clock");
173  }
174  }
175 
176  break;
177  }
178 
179  default:
180  break;
181  }
182 }
183 
184 uint64_t
186 {
187  // Only return synchronised stamp if we have converged to a good value
188  if (sync_converged()) {
189  return usec + (int64_t)_time_offset;
190 
191  } else {
192  return hrt_absolute_time();
193  }
194 }
195 
196 bool
198 {
199  return _sequence >= CONVERGENCE_WINDOW;
200 }
201 
202 void
203 MavlinkTimesync::add_sample(int64_t offset_us)
204 {
205  /* Online exponential smoothing filter. The derivative of the estimate is also
206  * estimated in order to produce an estimate without steady state lag:
207  * https://en.wikipedia.org/wiki/Exponential_smoothing#Double_exponential_smoothing
208  */
209 
210  double time_offset_prev = _time_offset;
211 
212  if (_sequence == 0) { // First offset sample
213  _time_offset = offset_us;
214 
215  } else {
216  // Update the clock offset estimate
217  _time_offset = _filter_alpha * offset_us + (1.0 - _filter_alpha) * (_time_offset + _time_skew);
218 
219  // Update the clock skew estimate
220  _time_skew = _filter_beta * (_time_offset - time_offset_prev) + (1.0 - _filter_beta) * _time_skew;
221  }
222 
223 }
224 
225 void
227 {
228  // Do a full reset of all statistics and parameters
229  _sequence = 0;
230  _time_offset = 0.0;
231  _time_skew = 0.0;
235  _high_rtt_count = 0;
236 
237 }
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
bool publish(const T &data)
Publish the struct.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).