PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_timesync.h
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.h
36  * Mavlink time synchroniser definition.
37  *
38  * @author Mohammed Kabir <mhkabir98@gmail.com>
39  */
40 
41 #pragma once
42 
43 #include "mavlink_bridge_header.h"
44 
47 
48 #include <drivers/drv_hrt.h>
49 
50 #include <math.h>
51 #include <float.h>
52 
53 using namespace time_literals;
54 
55 static constexpr time_t PX4_EPOCH_SECS = 1234567890ULL;
56 
57 // Filter gains
58 //
59 // Alpha : Used to smooth the overall clock offset estimate. Smaller values will lead
60 // to a smoother estimate, but track time drift more slowly, introducing a bias
61 // in the estimate. Larger values will cause low-amplitude oscillations.
62 //
63 // Beta : Used to smooth the clock skew estimate. Smaller values will lead to a
64 // tighter estimation of the skew (derivative), but will negatively affect how fast the
65 // filter reacts to clock skewing (e.g cause by temperature changes to the oscillator).
66 // Larger values will cause large-amplitude oscillations.
67 static constexpr double ALPHA_GAIN_INITIAL = 0.05;
68 static constexpr double BETA_GAIN_INITIAL = 0.05;
69 static constexpr double ALPHA_GAIN_FINAL = 0.003;
70 static constexpr double BETA_GAIN_FINAL = 0.003;
71 
72 // Filter gain scheduling
73 //
74 // The filter interpolates between the INITIAL and FINAL gains while the number of
75 // exhanged timesync packets is less than CONVERGENCE_WINDOW. A lower value will
76 // allow the timesync to converge faster, but with potentially less accurate initial
77 // offset and skew estimates.
78 static constexpr uint32_t CONVERGENCE_WINDOW = 500;
79 
80 // Outlier rejection and filter reset
81 //
82 // Samples with round-trip time higher than MAX_RTT_SAMPLE are not used to update the filter.
83 // More than MAX_CONSECUTIVE_HIGH_RTT number of such events in a row will throw a warning
84 // but not reset the filter.
85 // Samples whose calculated clock offset is more than MAX_DEVIATION_SAMPLE off from the current
86 // estimate are not used to update the filter. More than MAX_CONSECUTIVE_HIGH_DEVIATION number
87 // of such events in a row will reset the filter. This usually happens only due to a time jump
88 // on the remote system.
89 // TODO : automatically determine these using ping statistics?
90 static constexpr uint64_t MAX_RTT_SAMPLE = 10_ms;
91 static constexpr uint64_t MAX_DEVIATION_SAMPLE = 100_ms;
92 static constexpr uint32_t MAX_CONSECUTIVE_HIGH_RTT = 5;
93 static constexpr uint32_t MAX_CONSECUTIVE_HIGH_DEVIATION = 5;
94 
95 class Mavlink;
96 
98 {
99 public:
100  explicit MavlinkTimesync(Mavlink *mavlink);
101  ~MavlinkTimesync() = default;
102 
103  void handle_message(const mavlink_message_t *msg);
104 
105  /**
106  * Convert remote timestamp to local hrt time (usec)
107  * Use synchronised time if available, monotonic boot time otherwise
108  */
109  uint64_t sync_stamp(uint64_t usec);
110 
111 private:
112 
113  /* do not allow top copying this class */
115  MavlinkTimesync &operator = (const MavlinkTimesync &);
116 
117 protected:
118 
119  /**
120  * Online exponential filter to smooth time offset
121  */
122  void add_sample(int64_t offset_us);
123 
124  /**
125  * Return true if the timesync algorithm converged to a good estimate,
126  * return false otherwise
127  */
128  bool sync_converged();
129 
130  /**
131  * Reset the exponential filter and its states
132  */
133  void reset_filter();
134 
135  uORB::PublicationMulti<timesync_status_s> _timesync_status_pub{ORB_ID(timesync_status)};
136 
137  uint32_t _sequence{0};
138 
139  // Timesync statistics
140  double _time_offset{0};
141  double _time_skew{0};
142 
143  // Filter parameters
144  double _filter_alpha{ALPHA_GAIN_INITIAL};
145  double _filter_beta{BETA_GAIN_INITIAL};
146 
147  // Outlier rejection and filter reset
148  uint32_t _high_deviation_count{0};
149  uint32_t _high_rtt_count{0};
150 
152 };
High-resolution timer with callouts and timekeeping.
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87