10 #if UAVCAN_KINETIS_TIMER_NUMBER    18 # define TIMX_IRQHandler         UAVCAN_KINETIS_GLUE3(PIT, UAVCAN_KINETIS_TIMER_NUMBER, _IRQHandler)    19 # define TIMX                    (KINETIS_PIT_BASE + (UAVCAN_KINETIS_TIMER_NUMBER << 4))    20 # define TMR_REG(o)              (TIMX + (o))    21 # define TIMX_INPUT_CLOCK        BOARD_BUS_FREQ    22 # define TIMX_INTERRUPT_FREQ     16    23 # define TIMX_IRQn               UAVCAN_KINETIS_GLUE2(KINETIS_IRQ_PITCH, UAVCAN_KINETIS_TIMER_NUMBER)    25 # if UAVCAN_KINETIS_TIMER_NUMBER >= 0 && UAVCAN_KINETIS_TIMER_NUMBER <= 3    26 #  define KINETIS_PIT_LDVAL_OFFSET KINETIS_PIT_LDVAL0_OFFSET    27 #  define KINETIS_PIT_CVAL_OFFSET  KINETIS_PIT_CVAL0_OFFSET    28 #  define KINETIS_PIT_TCTRL_OFFSET KINETIS_PIT_TCTRL0_OFFSET    29 #  define KINETIS_PIT_TFLG_OFFSET  KINETIS_PIT_TFLG0_OFFSET    31 #  error "This UAVCAN_KINETIS_TIMER_NUMBER is not supported yet"    43 const uavcan::uint32_t CountsPerPeriod = (TIMX_INPUT_CLOCK / TIMX_INTERRUPT_FREQ);
    44 const uavcan::uint32_t CountsPerUs = (TIMX_INPUT_CLOCK / 1000000);
    45 const uavcan::uint32_t USecPerOverflow = (1000000 / TIMX_INTERRUPT_FREQ);
    49 bool initialized = 
false;
    52 bool utc_locked = 
false;
    53 uavcan::uint32_t utc_jump_cnt = 0;
    54 UtcSyncParams utc_sync_params;
    55 float utc_prev_adj = 0;
    56 float utc_rel_rate_ppm = 0;
    57 float utc_rel_rate_error_integral = 0;
    58 uavcan::int32_t utc_accumulated_correction_nsec = 0;
    59 uavcan::int32_t utc_correction_nsec_per_overflow = 0;
    60 uavcan::MonotonicTime prev_utc_adj_at;
    62 uavcan::uint64_t time_mono = 0;
    63 uavcan::uint64_t time_utc = 0;
    69     CriticalSectionLocker 
lock;
    78     irq_attach(TIMX_IRQn, &TIMX_IRQHandler, NULL);
    81     modifyreg32(KINETIS_SIM_SCGC6, 0, SIM_SCGC6_PIT);
    84     putreg32(0, KINETIS_PIT_MCR);
    88     putreg32(CountsPerPeriod - 1, TMR_REG(KINETIS_PIT_LDVAL_OFFSET));
    89     putreg32(PIT_TCTRL_TEN | PIT_TCTRL_TIE, TMR_REG(KINETIS_PIT_TCTRL_OFFSET));     
    99     up_prioritize_irq(TIMX_IRQn, NVIC_SYSH_HIGH_PRIORITY);
   101     up_enable_irq(TIMX_IRQn);
   104 void setUtc(uavcan::UtcTime time)
   106     MutexLocker mlocker(mutex);
   107     UAVCAN_ASSERT(initialized);
   110         CriticalSectionLocker locker;
   111         time_utc = time.toUSec();
   118     utc_rel_rate_ppm = 0;
   121 static uavcan::uint64_t sampleUtcFromCriticalSection()
   123     UAVCAN_ASSERT(initialized);
   124     UAVCAN_ASSERT(getreg32(TMR_REG(KINETIS_PIT_TCTRL_OFFSET)) & PIT_TCTRL_TIE);
   126     volatile uavcan::uint64_t time = time_utc;
   127     volatile uavcan::uint32_t cnt = CountsPerPeriod - getreg32(TMR_REG(KINETIS_PIT_CVAL_OFFSET));
   129     if (getreg32(TMR_REG(KINETIS_PIT_TFLG_OFFSET)) & PIT_TFLG_TIF) {
   130         cnt = CountsPerPeriod - getreg32(TMR_REG(KINETIS_PIT_CVAL_OFFSET));
   131         const uavcan::int32_t add = uavcan::int32_t(USecPerOverflow) +
   132                         (utc_accumulated_correction_nsec + utc_correction_nsec_per_overflow) / 1000;
   133         time = uavcan::uint64_t(uavcan::int64_t(time) + add);
   136     return time + (cnt / CountsPerUs);
   141     return utc_set ? sampleUtcFromCriticalSection() : 0;
   146     uavcan::uint64_t usec = 0;
   149         CriticalSectionLocker locker;
   151         volatile uavcan::uint64_t time = time_mono;
   152         volatile uavcan::uint32_t cnt = CountsPerPeriod - getreg32(TMR_REG(KINETIS_PIT_CVAL_OFFSET));
   154         if (getreg32(TMR_REG(KINETIS_PIT_TFLG_OFFSET)) & PIT_TFLG_TIF) {
   155             cnt = CountsPerPeriod - getreg32(TMR_REG(KINETIS_PIT_CVAL_OFFSET));
   156             time += USecPerOverflow;
   159         usec = time + (cnt / CountsPerUs);
   163     return uavcan::MonotonicTime::fromUSec(usec);
   170         uavcan::uint64_t usec = 0;
   172             CriticalSectionLocker locker;
   173             usec = sampleUtcFromCriticalSection();
   175         return uavcan::UtcTime::fromUSec(usec);
   178     return uavcan::UtcTime();
   181 static float lowpass(
float xold, 
float xnew, 
float corner, 
float dt)
   183     const float tau = 1.F / corner;
   184     return (dt * xnew + tau * xold) / (dt + tau);
   187 static void updateRatePID(uavcan::UtcDuration adjustment)
   190     const float dt = float((ts - prev_utc_adj_at).toUSec()) / 1e6F;
   191     prev_utc_adj_at = ts;
   192     const float adj_usec = float(adjustment.toUSec());
   198     const float target_rel_rate_ppm = adj_usec * utc_sync_params.offset_p;
   204     const float new_rel_rate_ppm = (utc_prev_adj - adj_usec) / dt;     
   205     utc_prev_adj = adj_usec;
   206     utc_rel_rate_ppm = lowpass(utc_rel_rate_ppm, new_rel_rate_ppm, utc_sync_params.rate_error_corner_freq, dt);
   208     const float rel_rate_error = target_rel_rate_ppm - utc_rel_rate_ppm;
   211         utc_rel_rate_error_integral = 0;
   214         utc_rel_rate_error_integral += rel_rate_error * dt * utc_sync_params.rate_i;
   215         utc_rel_rate_error_integral =
   216             uavcan::max(utc_rel_rate_error_integral, -utc_sync_params.max_rate_correction_ppm);
   217         utc_rel_rate_error_integral =
   218             uavcan::min(utc_rel_rate_error_integral, utc_sync_params.max_rate_correction_ppm);
   224     float total_rate_correction_ppm = rel_rate_error + utc_rel_rate_error_integral;
   225     total_rate_correction_ppm = 
uavcan::max(total_rate_correction_ppm, -utc_sync_params.max_rate_correction_ppm);
   226     total_rate_correction_ppm = 
uavcan::min(total_rate_correction_ppm, utc_sync_params.max_rate_correction_ppm);
   228     utc_correction_nsec_per_overflow = uavcan::int32_t((USecPerOverflow * 1000) * (total_rate_correction_ppm / 1e6F));
   235 void adjustUtc(uavcan::UtcDuration adjustment)
   237     MutexLocker mlocker(mutex);
   238     UAVCAN_ASSERT(initialized);
   240     if (adjustment.getAbs() > utc_sync_params.min_jump || !utc_set) {
   241         const uavcan::int64_t adj_usec = adjustment.toUSec();
   244             CriticalSectionLocker locker;
   246             if ((adj_usec < 0) && uavcan::uint64_t(-adj_usec) > time_utc) {
   250                 time_utc = uavcan::uint64_t(uavcan::int64_t(time_utc) + adj_usec);
   258         utc_rel_rate_ppm = 0;
   261         updateRatePID(adjustment);
   265                 (
std::abs(utc_rel_rate_ppm) < utc_sync_params.lock_thres_rate_ppm) &&
   266                 (
std::abs(utc_prev_adj) < float(utc_sync_params.lock_thres_offset.toUSec()));
   273     MutexLocker mlocker(mutex);
   274     const float rate_correction_mult = float(utc_correction_nsec_per_overflow) / float(USecPerOverflow * 1000);
   275     return 1e6F * rate_correction_mult;
   280     MutexLocker mlocker(mutex);
   286     MutexLocker mlocker(mutex);
   292     MutexLocker mlocker(mutex);
   293     return utc_sync_params;
   298     MutexLocker mlocker(mutex);
   300     utc_sync_params = params;
   307     static union SystemClockStorage {
   308         uavcan::uint8_t buffer[
sizeof(SystemClock)];
   309         long long _aligner_1;
   310         long double _aligner_2;
   313     SystemClock *
const ptr = 
reinterpret_cast<SystemClock *
>(storage.buffer);
   315     if (!clock::initialized) {
   316         MutexLocker mlocker(clock::mutex);
   318         new (ptr)SystemClock();
   334     putreg32(PIT_TFLG_TIF, TMR_REG(KINETIS_PIT_TFLG_OFFSET));
   337     UAVCAN_ASSERT(initialized);
   339     time_mono += USecPerOverflow;
   342         time_utc += USecPerOverflow;
   343         utc_accumulated_correction_nsec += utc_correction_nsec_per_overflow;
   345         if (
std::abs(utc_accumulated_correction_nsec) >= 1000) {
   346             time_utc = uavcan::uint64_t(uavcan::int64_t(time_utc) + utc_accumulated_correction_nsec / 1000);
   347             utc_accumulated_correction_nsec %= 1000;
   351         if (utc_correction_nsec_per_overflow > 0) {
   352             utc_correction_nsec_per_overflow--;
   354         } 
else if (utc_correction_nsec_per_overflow < 0) {
   355             utc_correction_nsec_per_overflow++;
 void setUtcSyncParams(const UtcSyncParams ¶ms)
 
UtcSyncParams getUtcSyncParams()
UTC sync params get/set. 
 
void init()
Starts the clock. 
 
float getUtcRateCorrectionPPM()
Clock rate error. 
 
bool isUtcLocked()
Whether UTC is synchronized and locked. 
 
uavcan::UtcTime getUtc()
Returns UTC time if it has been set, otherwise returns zero time. 
 
uavcan::MonotonicTime getMonotonic()
Returns current monotonic time since the moment when clock::init() was called. 
 
uavcan::uint64_t getUtcUSecFromCanInterrupt()
 
static SystemClock & instance()
Calls clock::init() as needed. 
 
#define UAVCAN_KINETIS_IRQ_HANDLER(id)
IRQ handler macros. 
 
constexpr _Tp min(_Tp a, _Tp b)
 
uavcan::uint32_t getUtcJumpCount()
Number of non-gradual adjustments performed so far. 
 
constexpr _Tp max(_Tp a, _Tp b)
 
void setUtc(uavcan::UtcTime time)
Sets the driver's notion of the system UTC. 
 
Dual< Scalar, N > abs(const Dual< Scalar, N > &a)
 
void adjustUtc(uavcan::UtcDuration adjustment)
Performs UTC phase and frequency adjustment.