PX4 Firmware
PX4 Autopilot Software http://px4.io
uc_stm32_clock.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
5 #include <uavcan_stm32/clock.hpp>
7 #include "internal.hpp"
8 
9 #if UAVCAN_STM32_TIMER_NUMBER
10 
11 #include <cassert>
12 #include <math.h>
13 
14 /*
15  * Timer instance
16  */
17 # if UAVCAN_STM32_NUTTX
18 # define TIMX UAVCAN_STM32_GLUE3(STM32_TIM, UAVCAN_STM32_TIMER_NUMBER, _BASE)
19 # define TMR_REG(o) (TIMX + (o))
20 # define TIMX_INPUT_CLOCK UAVCAN_STM32_GLUE3(STM32_APB1_TIM, UAVCAN_STM32_TIMER_NUMBER, _CLKIN)
21 
22 # define TIMX_IRQn UAVCAN_STM32_GLUE2(STM32_IRQ_TIM, UAVCAN_STM32_TIMER_NUMBER)
23 # endif
24 
25 # if UAVCAN_STM32_TIMER_NUMBER >= 2 && UAVCAN_STM32_TIMER_NUMBER <= 7
26 # define TIMX_RCC_ENR RCC->APB1ENR
27 # define TIMX_RCC_RSTR RCC->APB1RSTR
28 # define TIMX_RCC_ENR_MASK UAVCAN_STM32_GLUE3(RCC_APB1ENR_TIM, UAVCAN_STM32_TIMER_NUMBER, EN)
29 # define TIMX_RCC_RSTR_MASK UAVCAN_STM32_GLUE3(RCC_APB1RSTR_TIM, UAVCAN_STM32_TIMER_NUMBER, RST)
30 # else
31 # error "This UAVCAN_STM32_TIMER_NUMBER is not supported yet"
32 # endif
33 
34 /**
35  * UAVCAN_STM32_TIMX_INPUT_CLOCK can be used to manually override the auto-detected timer clock speed.
36  * This is useful at least with certain versions of ChibiOS which do not support the bit
37  * RCC_DKCFGR.TIMPRE that is available in newer models of STM32. In that case, if TIMPRE is active,
38  * the auto-detected value of TIMX_INPUT_CLOCK will be twice lower than the actual clock speed.
39  * Read this for additional context: http://www.chibios.com/forum/viewtopic.php?f=35&t=3870
40  * A normal way to use the override feature is to provide an alternative macro, e.g.:
41  *
42  * -DUAVCAN_STM32_TIMX_INPUT_CLOCK=STM32_HCLK
43  *
44  * Alternatively, the new clock rate can be specified directly.
45  */
46 # ifdef UAVCAN_STM32_TIMX_INPUT_CLOCK
47 # undef TIMX_INPUT_CLOCK
48 # define TIMX_INPUT_CLOCK UAVCAN_STM32_TIMX_INPUT_CLOCK
49 # endif
50 
51 extern "C" UAVCAN_STM32_IRQ_HANDLER(TIMX_IRQHandler);
52 
53 namespace uavcan_stm32
54 {
55 namespace clock
56 {
57 namespace
58 {
59 
60 const uavcan::uint32_t USecPerOverflow = 65536;
61 
62 Mutex mutex;
63 
64 bool initialized = false;
65 
66 bool utc_set = false;
67 bool utc_locked = false;
68 uavcan::uint32_t utc_jump_cnt = 0;
69 UtcSyncParams utc_sync_params;
70 float utc_prev_adj = 0;
71 float utc_rel_rate_ppm = 0;
72 float utc_rel_rate_error_integral = 0;
73 uavcan::int32_t utc_accumulated_correction_nsec = 0;
74 uavcan::int32_t utc_correction_nsec_per_overflow = 0;
75 uavcan::MonotonicTime prev_utc_adj_at;
76 
77 uavcan::uint64_t time_mono = 0;
78 uavcan::uint64_t time_utc = 0;
79 
80 }
81 
82 
83 void init()
84 {
85  CriticalSectionLocker lock;
86 
87  if (initialized) {
88  return;
89  }
90 
91  initialized = true;
92 
93 
94 # if UAVCAN_STM32_NUTTX
95 
96  // Attach IRQ
97  irq_attach(TIMX_IRQn, &TIMX_IRQHandler, NULL);
98 
99  // Power-on and reset
100  modifyreg32(STM32_RCC_APB1ENR, 0, TIMX_RCC_ENR_MASK);
101  modifyreg32(STM32_RCC_APB1RSTR, 0, TIMX_RCC_RSTR_MASK);
102  modifyreg32(STM32_RCC_APB1RSTR, TIMX_RCC_RSTR_MASK, 0);
103 
104 
105  // Start the timer
106  putreg32(0xFFFF, TMR_REG(STM32_BTIM_ARR_OFFSET));
107  putreg16(((TIMX_INPUT_CLOCK / 1000000) - 1), TMR_REG(STM32_BTIM_PSC_OFFSET));
108  putreg16(BTIM_CR1_URS, TMR_REG(STM32_BTIM_CR1_OFFSET));
109  putreg16(0, TMR_REG(STM32_BTIM_SR_OFFSET));
110  putreg16(BTIM_EGR_UG, TMR_REG(STM32_BTIM_EGR_OFFSET)); // Reload immediately
111  putreg16(BTIM_DIER_UIE, TMR_REG(STM32_BTIM_DIER_OFFSET));
112  putreg16(BTIM_CR1_CEN, TMR_REG(STM32_BTIM_CR1_OFFSET)); // Start
113 
114  // Prioritize and Enable IRQ
115 // todo: Currently changing the NVIC_SYSH_HIGH_PRIORITY is HARD faulting
116 // need to investigate
117 // up_prioritize_irq(TIMX_IRQn, NVIC_SYSH_HIGH_PRIORITY);
118  up_enable_irq(TIMX_IRQn);
119 
120 # endif
121 }
122 
123 void setUtc(uavcan::UtcTime time)
124 {
125  MutexLocker mlocker(mutex);
126  UAVCAN_ASSERT(initialized);
127 
128  {
129  CriticalSectionLocker locker;
130  time_utc = time.toUSec();
131  }
132 
133  utc_set = true;
134  utc_locked = false;
135  utc_jump_cnt++;
136  utc_prev_adj = 0;
137  utc_rel_rate_ppm = 0;
138 }
139 
140 static uavcan::uint64_t sampleUtcFromCriticalSection()
141 {
142 # if UAVCAN_STM32_NUTTX
143 
144  UAVCAN_ASSERT(initialized);
145  UAVCAN_ASSERT(getreg16(TMR_REG(STM32_BTIM_DIER_OFFSET)) & BTIM_DIER_UIE);
146 
147  volatile uavcan::uint64_t time = time_utc;
148  volatile uavcan::uint32_t cnt = getreg16(TMR_REG(STM32_BTIM_CNT_OFFSET));
149 
150  if (getreg16(TMR_REG(STM32_BTIM_SR_OFFSET)) & BTIM_SR_UIF) {
151  cnt = getreg16(TMR_REG(STM32_BTIM_CNT_OFFSET));
152  const uavcan::int32_t add = uavcan::int32_t(USecPerOverflow) +
153  (utc_accumulated_correction_nsec + utc_correction_nsec_per_overflow) / 1000;
154  time = uavcan::uint64_t(uavcan::int64_t(time) + add);
155  }
156 
157  return time + cnt;
158 # endif
159 }
160 
161 uavcan::uint64_t getUtcUSecFromCanInterrupt()
162 {
163  return utc_set ? sampleUtcFromCriticalSection() : 0;
164 }
165 
166 uavcan::MonotonicTime getMonotonic()
167 {
168  uavcan::uint64_t usec = 0;
169  // Scope Critical section
170  {
171  CriticalSectionLocker locker;
172 
173  volatile uavcan::uint64_t time = time_mono;
174 
175 # if UAVCAN_STM32_NUTTX
176 
177  volatile uavcan::uint32_t cnt = getreg16(TMR_REG(STM32_BTIM_CNT_OFFSET));
178 
179  if (getreg16(TMR_REG(STM32_BTIM_SR_OFFSET)) & BTIM_SR_UIF) {
180  cnt = getreg16(TMR_REG(STM32_BTIM_CNT_OFFSET));
181 # endif
182  time += USecPerOverflow;
183  }
184 
185  usec = time + cnt;
186 
187 # ifndef NDEBUG
188  static uavcan::uint64_t prev_usec = 0; // Self-test
189  UAVCAN_ASSERT(prev_usec <= usec);
190  (void)prev_usec;
191  prev_usec = usec;
192 # endif
193  } // End Scope Critical section
194 
195  return uavcan::MonotonicTime::fromUSec(usec);
196 }
197 
198 uavcan::UtcTime getUtc()
199 {
200  if (utc_set) {
201  uavcan::uint64_t usec = 0;
202  {
203  CriticalSectionLocker locker;
204  usec = sampleUtcFromCriticalSection();
205  }
206  return uavcan::UtcTime::fromUSec(usec);
207  }
208 
209  return uavcan::UtcTime();
210 }
211 
212 static float lowpass(float xold, float xnew, float corner, float dt)
213 {
214  const float tau = 1.F / corner;
215  return (dt * xnew + tau * xold) / (dt + tau);
216 }
217 
218 static void updateRatePID(uavcan::UtcDuration adjustment)
219 {
220  const uavcan::MonotonicTime ts = getMonotonic();
221  const float dt = float((ts - prev_utc_adj_at).toUSec()) / 1e6F;
222  prev_utc_adj_at = ts;
223  const float adj_usec = float(adjustment.toUSec());
224 
225  /*
226  * Target relative rate in PPM
227  * Positive to go faster
228  */
229  const float target_rel_rate_ppm = adj_usec * utc_sync_params.offset_p;
230 
231  /*
232  * Current relative rate in PPM
233  * Positive if the local clock is faster
234  */
235  const float new_rel_rate_ppm = (utc_prev_adj - adj_usec) / dt; // rate error in [usec/sec], which is PPM
236  utc_prev_adj = adj_usec;
237  utc_rel_rate_ppm = lowpass(utc_rel_rate_ppm, new_rel_rate_ppm, utc_sync_params.rate_error_corner_freq, dt);
238 
239  const float rel_rate_error = target_rel_rate_ppm - utc_rel_rate_ppm;
240 
241  if (dt > 10) {
242  utc_rel_rate_error_integral = 0;
243 
244  } else {
245  utc_rel_rate_error_integral += rel_rate_error * dt * utc_sync_params.rate_i;
246  utc_rel_rate_error_integral =
247  uavcan::max(utc_rel_rate_error_integral, -utc_sync_params.max_rate_correction_ppm);
248  utc_rel_rate_error_integral =
249  uavcan::min(utc_rel_rate_error_integral, utc_sync_params.max_rate_correction_ppm);
250  }
251 
252  /*
253  * Rate controller
254  */
255  float total_rate_correction_ppm = rel_rate_error + utc_rel_rate_error_integral;
256  total_rate_correction_ppm = uavcan::max(total_rate_correction_ppm, -utc_sync_params.max_rate_correction_ppm);
257  total_rate_correction_ppm = uavcan::min(total_rate_correction_ppm, utc_sync_params.max_rate_correction_ppm);
258 
259  utc_correction_nsec_per_overflow = uavcan::int32_t((USecPerOverflow * 1000) * (total_rate_correction_ppm / 1e6F));
260 
261 // syslog("$ adj=%f rel_rate=%f rel_rate_eint=%f tgt_rel_rate=%f ppm=%f\n",
262 // adj_usec, utc_rel_rate_ppm, utc_rel_rate_error_integral, target_rel_rate_ppm,
263 // total_rate_correction_ppm);
264 }
265 
266 void adjustUtc(uavcan::UtcDuration adjustment)
267 {
268  MutexLocker mlocker(mutex);
269  UAVCAN_ASSERT(initialized);
270 
271  if (adjustment.getAbs() > utc_sync_params.min_jump || !utc_set) {
272  const uavcan::int64_t adj_usec = adjustment.toUSec();
273 
274  {
275  CriticalSectionLocker locker;
276 
277  if ((adj_usec < 0) && uavcan::uint64_t(-adj_usec) > time_utc) {
278  time_utc = 1;
279 
280  } else {
281  time_utc = uavcan::uint64_t(uavcan::int64_t(time_utc) + adj_usec);
282  }
283  }
284 
285  utc_set = true;
286  utc_locked = false;
287  utc_jump_cnt++;
288  utc_prev_adj = 0;
289  utc_rel_rate_ppm = 0;
290 
291  } else {
292  updateRatePID(adjustment);
293 
294  if (!utc_locked) {
295  utc_locked =
296  (std::abs(utc_rel_rate_ppm) < utc_sync_params.lock_thres_rate_ppm) &&
297  (std::abs(utc_prev_adj) < float(utc_sync_params.lock_thres_offset.toUSec()));
298  }
299  }
300 }
301 
303 {
304  MutexLocker mlocker(mutex);
305  const float rate_correction_mult = float(utc_correction_nsec_per_overflow) / float(USecPerOverflow * 1000);
306  return 1e6F * rate_correction_mult;
307 }
308 
309 uavcan::uint32_t getUtcJumpCount()
310 {
311  MutexLocker mlocker(mutex);
312  return utc_jump_cnt;
313 }
314 
315 bool isUtcLocked()
316 {
317  MutexLocker mlocker(mutex);
318  return utc_locked;
319 }
320 
321 UtcSyncParams getUtcSyncParams()
322 {
323  MutexLocker mlocker(mutex);
324  return utc_sync_params;
325 }
326 
327 void setUtcSyncParams(const UtcSyncParams &params)
328 {
329  MutexLocker mlocker(mutex);
330  // Add some sanity check
331  utc_sync_params = params;
332 }
333 
334 } // namespace clock
335 
336 SystemClock &SystemClock::instance()
337 {
338  static union SystemClockStorage {
339  uavcan::uint8_t buffer[sizeof(SystemClock)];
340  long long _aligner_1;
341  long double _aligner_2;
342  } storage;
343 
344  SystemClock *const ptr = reinterpret_cast<SystemClock *>(storage.buffer);
345 
346  if (!clock::initialized) {
347  MutexLocker mlocker(clock::mutex);
348  clock::init();
349  new (ptr)SystemClock();
350  }
351 
352  return *ptr;
353 }
354 
355 } // namespace uavcan_stm32
356 
357 
358 /**
359  * Timer interrupt handler
360  */
361 
362 extern "C"
363 UAVCAN_STM32_IRQ_HANDLER(TIMX_IRQHandler)
364 {
365  UAVCAN_STM32_IRQ_PROLOGUE();
366 
367 # if UAVCAN_STM32_NUTTX
368  putreg16(0, TMR_REG(STM32_BTIM_SR_OFFSET));
369 # endif
370 
371  using namespace uavcan_stm32::clock;
372  UAVCAN_ASSERT(initialized);
373 
374  time_mono += USecPerOverflow;
375 
376  if (utc_set) {
377  time_utc += USecPerOverflow;
378  utc_accumulated_correction_nsec += utc_correction_nsec_per_overflow;
379 
380  if (std::abs(utc_accumulated_correction_nsec) >= 1000) {
381  time_utc = uavcan::uint64_t(uavcan::int64_t(time_utc) + utc_accumulated_correction_nsec / 1000);
382  utc_accumulated_correction_nsec %= 1000;
383  }
384 
385  // Correction decay - 1 nsec per 65536 usec
386  if (utc_correction_nsec_per_overflow > 0) {
387  utc_correction_nsec_per_overflow--;
388 
389  } else if (utc_correction_nsec_per_overflow < 0) {
390  utc_correction_nsec_per_overflow++;
391 
392  } else {
393  ; // Zero
394  }
395  }
396 
397  UAVCAN_STM32_IRQ_EPILOGUE();
398 }
399 
400 #endif
float getUtcRateCorrectionPPM()
Clock rate error.
uavcan::uint32_t getUtcJumpCount()
Number of non-gradual adjustments performed so far.
static SystemClock & instance()
Calls clock::init() as needed.
uavcan::uint64_t getUtcUSecFromCanInterrupt()
void adjustUtc(uavcan::UtcDuration adjustment)
Performs UTC phase and frequency adjustment.
UAVCAN_STM32_IRQ_HANDLER(CAN1_TX_IRQHandler)
UtcSyncParams getUtcSyncParams()
UTC sync params get/set.
uavcan::UtcTime getUtc()
Returns UTC time if it has been set, otherwise returns zero time.
constexpr _Tp min(_Tp a, _Tp b)
Definition: Limits.hpp:54
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
float dt
Definition: px4io.c:73
void init()
Starts the clock.
bool isUtcLocked()
Whether UTC is synchronized and locked.
uavcan::MonotonicTime getMonotonic()
Returns current monotonic time since the moment when clock::init() was called.
void setUtcSyncParams(const UtcSyncParams &params)
Dual< Scalar, N > abs(const Dual< Scalar, N > &a)
Definition: Dual.hpp:196
void setUtc(uavcan::UtcTime time)
Sets the driver&#39;s notion of the system UTC.