Commit 82d141c7fec534c23fd00d0f59658706981f9596

Authored by Antonio Carlos Domínguez Brito
1 parent 0751140f
Exists in master

action objects period now are specified using hundredths of usecs., instead of usecs.

CMakeLists.txt
... ... @@ -56,6 +56,7 @@ set(
56 56 capture_test
57 57 pwm_capture_test
58 58 action_test
  59 + wave_example
59 60 )
60 61  
61 62 foreach(src_example ${TC_EXAMPLES})
... ...
README.md
... ... @@ -44,7 +44,7 @@ Capture objects take advantage of TC module channels in *capture* mode to measur
44 44  
45 45 In addition, capture objects can tell you how many pulses they have captured so far using member function *get_duty_period_and_pulses()*.
46 46  
47   -### 2.1 Fast signals and capture objects
  47 +### 2.1. Fast signals and capture objects
48 48  
49 49 When capturing signals capture objects do intensive use of interrupts associated to the TC channel associated with the specific object. If the signal to capture is very fast (pulse duration around 1 microsecond or less), some interrupts will be missed to track the signal. Internally the TC channel in capture mode registers those situations with the signaling of a "load overrun" of one of the capture registers RA or RB (more details in ATSAM3X8E data sheet). Evidently, this may also happen in an application where the use of interrupts is very high, even if the signal to capture is not so fast. In any case, specially with fast signals (frequencies of around 1 Mhz) this massive use of interrupts could provoke the freezing of the CPU, since all CPU time was invested on interrupts. To avoid that situation, the capture object stops capturing when it detects too much overrun events, keeping internally the duty and period of the last pulse captured. Function *get_duty_and_period()* returns a status value where we can check if the capture objects was overrun and/or stopped. Here a snippet of code from example *pwm_capture_test.ino* illustrating its use:
50 50  
... ... @@ -82,7 +82,7 @@ Action objects are associated with a specific TC channel, whether TC0, TC1, TC2,
82 82 action_tc0_declaration();
83 83 ```
84 84  
85   -To start using an action object we have to call action object's *start()* member function to establish the callback and the period (in microseconds) to call the callback. Here a fragment of code illustrating its use in example *action_test.ino*:
  85 +To start using an action object we have to call action object's *start()* member function to establish the callback and the period (in hundredths of microseconds) to call the callback. Here a fragment of code illustrating its use in example *action_test.ino*:
86 86  
87 87 ```
88 88 action_tc0.start(CALLBACK_PERIOD,set_led_action,&action_ctx);
... ... @@ -110,11 +110,13 @@ In addition you must add the flag -std=gnu++11 for compiling. For doing that add
110 110  
111 111 ### 5. Examples
112 112  
113   -On the examples directory you have available a basic example for using a capture object, *capture_test.ino*, and an example for using an action object, *action_test.ino*.
  113 +On the examples directory you have available a basic example for using a capture object, *capture_test.ino*, and two examples for using action objects, *action_test.ino* and *wave_example.ino*.
114 114  
115 115 There is third example, *pwm_capture_test.ino* which is specifically designed to check the capture objects with fast signals. For this example it is necessary the use of library pwm_lib, available at [https://github.com/antodom/pwm_lib](https://github.com/antodom/pwm_lib).
116 116  
117   -I hope all three examples are self-explaining.
  117 +The last example, *wave_example.ino*, shows how to use action objects to send a byte through a pin using a digital wave.
  118 +
  119 +I hope all four examples are self-explaining.
118 120  
119 121 ### 6. Incompatibilities
120 122  
... ... @@ -126,6 +128,7 @@ For compiling on command line using CMake, just proceed in the following manner:
126 128  
127 129 1. Set the following environment variables (a good place to put them is on .bashrc):
128 130 * Set `ARDUINO_DUE_ROOT_PATH` to `~/.arduino15/packages/arduino/`.
  131 + * Set 'ARDUINO_DUE_VERSION' to `1.6.17`.
129 132 * Set `ARDUINO_UNO_ROOT_PATH` to the path where you have installed the Arduino IDE, for example, `~/installations/arduino-1.6.5`.
130 133 * Set `ARDUINO_IDE_LIBRARY_PATH` to the path for the Arduino IDE projects you have in preferences. For example, `~/arduino_projects`.
131 134  
... ...
examples/action_test/action_test.ino
... ... @@ -36,7 +36,7 @@
36 36  
37 37 using namespace arduino_due;
38 38  
39   -#define CALLBACK_PERIOD 100000 // usecs.
  39 +#define CALLBACK_PERIOD 10000000 // hundreths of usecs. (1e-8 secs.)
40 40 #define DELAY_TIME 2000 // msecs.
41 41  
42 42 // action_tc0 declaration
... ... @@ -79,7 +79,9 @@ void setup() {
79 79 Serial.println(" usecs.");
80 80 Serial.print("period: ");
81 81 Serial.print(action_tc0.get_period());
82   - Serial.println(" usecs.");
  82 + Serial.println(" hundreths of usecs. (1e-8 secs.)");
  83 + Serial.print("ticks: ");
  84 + Serial.println(action_tc0.ticks(CALLBACK_PERIOD));
83 85  
84 86 Serial.println("========================================================");
85 87 }
... ...
examples/wave_example/wave_example.ino 0 → 100644
... ... @@ -0,0 +1,180 @@
  1 +/**
  2 + ** tc_lib library
  3 + ** Copyright (C) 2016
  4 + **
  5 + ** Antonio C. Domínguez Brito <adominguez@iusiani.ulpgc.es>
  6 + ** División de Robótica y Oceanografía Computacional <www.roc.siani.es>
  7 + ** and Departamento de Informática y Sistemas <www.dis.ulpgc.es>
  8 + ** Universidad de Las Palmas de Gran Canaria (ULPGC) <www.ulpgc.es>
  9 + **
  10 + ** This file is part of the tc_lib library.
  11 + ** The tc_lib library is free software: you can redistribute it and/or modify
  12 + ** it under the terms of the GNU General Public License as published by
  13 + ** the Free Software Foundation, either version 3 of the License, or any
  14 + ** later version.
  15 + **
  16 + ** The tc_lib library is distributed in the hope that it will be useful,
  17 + ** but WITHOUT ANY WARRANTY; without even the implied warranty of
  18 + ** MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
  19 + ** Public License for more details.
  20 + **
  21 + ** You should have received a copy (COPYING file) of the GNU General Public
  22 + ** License along with the tc_lib library.
  23 + ** If not, see: <http://www.gnu.org/licenses/>.
  24 + **/
  25 +/*
  26 + * File: wave_test.ino
  27 + * Description: This is an example illustrating the use of the tc_lib library's
  28 + * action objects for generating a digital signal.
  29 + * Date: February 21st, 2017
  30 + * Author: Antonio C. Dominguez-Brito <adominguez@iusiani.ulpgc.es>
  31 + * ROC-SIANI - Universidad de Las Palmas de Gran Canaria - Spain
  32 + */
  33 +
  34 +#include "tc_lib.h"
  35 +
  36 +using namespace arduino_due;
  37 +
  38 +#define WAVE_PERIOD 500 // 240 //460 // 1200 //50000 // hundredths of usecs. (1e-8 msecs.)
  39 +#define WAVE_PIN 10
  40 +
  41 +#define CAPTURE_TIME_WINDOW 2500000 // usecs
  42 +
  43 +#define DELAY_TIME 2000 // msecs.
  44 +
  45 +// action_tc1 declaration, we use TC1 channel
  46 +action_tc1_declaration();
  47 +auto& action_obj=action_tc1;
  48 +
  49 +// capture_tc0 declaration
  50 +// NOTE: we will use capture_tc0 to verify the wave signal we will generate,
  51 +// using this example, in order to verify that the measured timing are right
  52 +// IMPORTANT: Take into account that for TC0 (TC0 and channel 0) the TIOA0 is
  53 +// PB25, which is pin 2 for Arduino DUE, so the capture pin in this example
  54 +// is pin 2. For the correspondence between all TIOA inputs for the different
  55 +// TC modules, you should consult uC Atmel ATSAM3X8E datasheet in section "36.
  56 +// Timer Counter (TC)"), and the Arduino pin mapping for the DUE.
  57 +capture_tc0_declaration();
  58 +auto& capture_pin2=capture_tc0;
  59 +
  60 +template<typename Action_Object>
  61 +class wave
  62 +{
  63 + public:
  64 +
  65 + wave(Action_Object& action_obj,uint32_t pin,uint32_t period)
  66 + : _bit_(8),
  67 + _action_obj_(action_obj),
  68 + _period_(period),
  69 + _pin_(pin)
  70 + {
  71 + _pio_p_=g_APinDescription[_pin_].pPort;
  72 + _mask_=g_APinDescription[_pin_].ulPin;
  73 +
  74 + // setting pin as output
  75 + pinMode(_pin_,HIGH);
  76 + }
  77 +
  78 + bool is_sending() { return (_bit_<8); }
  79 +
  80 + bool send(uint8_t data)
  81 + {
  82 + // only when the last data has been sent
  83 + // we accept another byte
  84 + if(is_sending()) return false;
  85 +
  86 + _data_=data; _bit_=0;
  87 +
  88 + return action_obj.start(
  89 + _period_,
  90 + _send_bit_callback_,
  91 + reinterpret_cast<void*>(this)
  92 + );
  93 + }
  94 +
  95 + private:
  96 +
  97 + volatile uint8_t _data_;
  98 + volatile uint32_t _bit_;
  99 + volatile uint32_t _period_;
  100 +
  101 + uint32_t _pin_;
  102 + Pio* _pio_p_;
  103 + uint32_t _mask_;
  104 +
  105 + Action_Object& _action_obj_;
  106 +
  107 + static void _send_bit_callback_(void* ptr)
  108 + {
  109 + wave* this_ptr=reinterpret_cast<wave*>(ptr);
  110 +
  111 + this_ptr->_send_bit_();
  112 + }
  113 +
  114 + void _send_bit_()
  115 + {
  116 + if(_data_ & (1<<_bit_))
  117 + PIO_Set(_pio_p_,_mask_);
  118 + else PIO_Clear(_pio_p_,_mask_);
  119 +
  120 + _bit_++;
  121 + //_bit_&=0x3;
  122 + if(_bit_>=8) action_obj.stop();
  123 + }
  124 +};
  125 +
  126 +wave<action_tc1_t> wave_obj(action_tc1,WAVE_PIN,WAVE_PERIOD);
  127 +
  128 +void setup() {
  129 + // put your setup code here, to run once:
  130 +
  131 + Serial.begin(9600);
  132 +
  133 + // capture_pin2 initialization
  134 + capture_pin2.config(CAPTURE_TIME_WINDOW);
  135 +
  136 + while(!wave_obj.send(0b01010101)) {}
  137 +
  138 + Serial.println("========================================================");
  139 +
  140 + Serial.print("max period: ");
  141 + Serial.print(action_tc1.max_period());
  142 + Serial.println(" hundreths of usecs.");
  143 + Serial.print("max period ticks: ");
  144 + Serial.println(action_tc1.ticks(action_tc1.max_period()));
  145 + Serial.print("period: ");
  146 + Serial.print(action_tc1.get_period());
  147 + Serial.println(" hundreths of usecs. (1e-8 secs.)");
  148 + Serial.print("ticks: ");
  149 + Serial.println(action_tc1.ticks(WAVE_PERIOD));
  150 +
  151 + Serial.println("========================================================");
  152 +
  153 +}
  154 +
  155 +void loop() {
  156 + // put your main code here,to run repeatedly:
  157 +
  158 + uint32_t status,duty,period;
  159 + status=capture_pin2.get_duty_and_period(duty,period);
  160 +
  161 + while(!wave_obj.send(0b01010101)) {}
  162 +
  163 + Serial.println("********************************************************");
  164 + Serial.print("--> [PIN "); Serial.print(WAVE_PIN);
  165 + Serial.print(" -> PIN 2] duty: ");
  166 + Serial.print(
  167 + static_cast<double>(duty)/
  168 + static_cast<double>(capture_pin2.ticks_per_usec()),
  169 + 3
  170 + );
  171 + Serial.print(" usecs. period: ");
  172 + Serial.print(
  173 + static_cast<double>(period)/
  174 + static_cast<double>(capture_pin2.ticks_per_usec()),
  175 + 3
  176 + );
  177 + Serial.println(" usecs.");
  178 +}
  179 +
  180 +
... ...
tc_defs.h
... ... @@ -84,15 +84,15 @@ namespace arduino_due
84 84  
85 85 static void start_interrupts()
86 86 {
87   - NVIC_ClearPendingIRQ(info::irq);
88   - NVIC_EnableIRQ(info::irq);
89   - TC_Start(info::tc_p,info::channel);
  87 + NVIC_ClearPendingIRQ(info::irq);
  88 + NVIC_EnableIRQ(info::irq);
  89 + TC_Start(info::tc_p,info::channel);
90 90 }
91 91  
92 92 static void stop_interrupts()
93 93 {
94   - NVIC_DisableIRQ(info::irq);
95   - TC_Stop(info::tc_p,info::channel);
  94 + NVIC_DisableIRQ(info::irq);
  95 + TC_Stop(info::tc_p,info::channel);
96 96 }
97 97  
98 98 static void config_interrupt() { NVIC_SetPriority(info::irq,0); }
... ... @@ -101,82 +101,82 @@ namespace arduino_due
101 101  
102 102 static void enable_lovr_interrupt()
103 103 {
104   - info::tc_p->TC_CHANNEL[info::channel].TC_IER=
105   - TC_IER_LOVRS;
  104 + info::tc_p->TC_CHANNEL[info::channel].TC_IER=
  105 + TC_IER_LOVRS;
106 106 }
107 107  
108 108 static bool is_enabled_lovr_interrupt()
109 109 {
110   - return (
111   - info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
112   - TC_IMR_LOVRS
113   - );
  110 + return (
  111 + info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
  112 + TC_IMR_LOVRS
  113 + );
114 114 }
115 115  
116 116 static void disable_lovr_interrupt()
117 117 {
118   - info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
119   - TC_IDR_LOVRS;
  118 + info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
  119 + TC_IDR_LOVRS;
120 120 }
121 121  
122 122 static void enable_ldra_interrupt()
123 123 {
124   - info::tc_p->TC_CHANNEL[info::channel].TC_IER=
125   - TC_IER_LDRAS;
  124 + info::tc_p->TC_CHANNEL[info::channel].TC_IER=
  125 + TC_IER_LDRAS;
126 126 }
127 127  
128 128 static bool is_enabled_ldra_interrupt()
129 129 {
130   - return (
131   - info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
132   - TC_IMR_LDRAS
133   - );
  130 + return (
  131 + info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
  132 + TC_IMR_LDRAS
  133 + );
134 134 }
135 135  
136 136 static void disable_ldra_interrupt()
137 137 {
138   - info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
139   - TC_IDR_LDRAS;
  138 + info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
  139 + TC_IDR_LDRAS;
140 140 }
141 141  
142 142 static void enable_ldrb_interrupt()
143 143 {
144   - info::tc_p->TC_CHANNEL[info::channel].TC_IER=
145   - TC_IER_LDRBS;
  144 + info::tc_p->TC_CHANNEL[info::channel].TC_IER=
  145 + TC_IER_LDRBS;
146 146 }
147 147  
148 148 static bool is_enabled_ldrb_interrupt()
149 149 {
150   - return (
151   - info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
152   - TC_IMR_LDRBS
153   - );
  150 + return (
  151 + info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
  152 + TC_IMR_LDRBS
  153 + );
154 154 }
155 155  
156 156 static void disable_ldrb_interrupt()
157 157 {
158   - info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
159   - TC_IDR_LDRBS;
  158 + info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
  159 + TC_IDR_LDRBS;
160 160 }
161 161  
162 162 static void enable_rc_interrupt()
163 163 {
164   - info::tc_p->TC_CHANNEL[info::channel].TC_IER=
165   - TC_IER_CPCS;
  164 + info::tc_p->TC_CHANNEL[info::channel].TC_IER=
  165 + TC_IER_CPCS;
166 166 }
167 167  
168 168 static bool is_enabled_rc_interrupt()
169 169 {
170   - return (
171   - info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
172   - TC_IMR_CPCS
173   - );
  170 + return (
  171 + info::tc_p->TC_CHANNEL[info::channel].TC_IMR &
  172 + TC_IMR_CPCS
  173 + );
174 174 }
175 175  
176 176 static void disable_rc_interrupt()
177 177 {
178   - info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
179   - TC_IDR_CPCS;
  178 + info::tc_p->TC_CHANNEL[info::channel].TC_IDR=
  179 + TC_IDR_CPCS;
180 180 }
181 181  
182 182 };
... ...
tc_lib.h
... ... @@ -239,8 +239,9 @@ namespace arduino_due
239 239 static constexpr uint32_t max_capture_window()
240 240 {
241 241 return
242   - static_cast<uint32_t>(static_cast<long long>(1<<32)-1) /
243   - ticks_per_usec();
  242 + static_cast<uint32_t>(
  243 + static_cast<long long>(1<<32)-static_cast<long long>(1)
  244 + ) / ticks_per_usec();
244 245 }
245 246  
246 247 uint32_t get_duty_and_period(
... ... @@ -407,10 +408,10 @@ namespace arduino_due
407 408 timer::info::channel,
408 409 TC_CMR_TCCLKS_TIMER_CLOCK1 | // clock prescaler set to /2
409 410 TC_CMR_CPCTRG | // timer reset on RC match
410   - TC_CMR_LDRA_RISING | // capture to RA on rising edge
411   - TC_CMR_LDRB_FALLING | // capture to RB on falling edge
412   - TC_CMR_ETRGEDG_FALLING | // external trigger on falling edge
413   - TC_CMR_ABETRG // external trigger on TIOA
  411 + TC_CMR_LDRA_RISING | // capture to RA on rising edge
  412 + TC_CMR_LDRB_FALLING | // capture to RB on falling edge
  413 + TC_CMR_ETRGEDG_FALLING | // external trigger on falling edge
  414 + TC_CMR_ABETRG // external trigger on TIOA
414 415 );
415 416  
416 417 // seting RC to the capture window
... ... @@ -433,23 +434,23 @@ namespace arduino_due
433 434 )
434 435 {
435 436 if( // load overrun on RA or RB
436   - (the_status & TC_SR_LOVRS) &&
437   - timer::is_enabled_lovr_interrupt()
  437 + (the_status & TC_SR_LOVRS) &&
  438 + timer::is_enabled_lovr_interrupt()
438 439 ) load_overrun();
439 440  
440 441 if( // RA loaded?
441   - (the_status & TC_SR_LDRAS) &&
442   - timer::is_enabled_ldra_interrupt()
  442 + (the_status & TC_SR_LDRAS) &&
  443 + timer::is_enabled_ldra_interrupt()
443 444 ) ra_loaded();
444 445  
445 446 if( // RB loaded?
446   - (the_status & TC_SR_LDRBS) &&
447   - timer::is_enabled_ldrb_interrupt()
  447 + (the_status & TC_SR_LDRBS) &&
  448 + timer::is_enabled_ldrb_interrupt()
448 449 ) rb_loaded();
449 450  
450 451 if( // RC compare interrupt?
451   - (the_status & TC_SR_CPCS) &&
452   - timer::is_enabled_rc_interrupt()
  452 + (the_status & TC_SR_CPCS) &&
  453 + timer::is_enabled_rc_interrupt()
453 454 ) rc_matched();
454 455 }
455 456  
... ... @@ -461,93 +462,112 @@ namespace arduino_due
461 462  
462 463 action() {}
463 464  
464   - ~action() {}
  465 + ~action() {}
465 466  
466 467 action(const action&) = delete;
467 468 action(action&&) = delete;
468   - action& operator=(const action&) = delete;
469   - action& operator=(action&&) = delete;
470   -
471   - bool start(
472   - uint32_t the_period,
473   - callback_t the_callback,
474   - void* the_user_ctx
475   - )
476   - { return _ctx_.start(the_period,the_callback,the_user_ctx); }
477   -
478   - void stop() { _ctx_.stop(); }
479   -
480   - void lock() { timer::disable_tc_interrupts(); }
481   - void unlock() { timer::enable_tc_interrupts(); }
482   -
483   - constexpr uint32_t max_period() { return _ctx_.max_period(); }
484   -
485   - // NOTE: get_period() returns 0 if the action is stopped
486   - uint32_t get_period() { return _ctx_.period; }
487   -
488   - static void tc_interrupt(uint32_t the_status)
489   - { _ctx_.tc_interrupt(the_status); }
490   -
491   - using timer = tc_core<TIMER>;
492   -
493   - private:
494   -
495   - struct _action_ctx_
496   - {
497   -
498   - _action_ctx_() { init(); }
499   -
500   - void init()
501   - { period=0; callback=[](void* dummy){}; user_ctx=nullptr; }
502   -
503   - void tc_interrupt(uint32_t the_status)
504   - {
505   - // RC compare interrupt
506   - if(
507   - (the_status & TC_SR_CPCS) &&
508   - timer::is_enabled_rc_interrupt()
509   - ) { callback(user_ctx); }
510   - }
511   -
512   - bool start(
513   - uint32_t the_period,
514   - callback_t the_callback,
515   - void* user_ctx
516   - );
517   -
518   - void stop()
519   - {
520   - timer::disable_rc_interrupt();
521   -
522   - timer::stop_interrupts();
523   - pmc_disable_periph_clk(uint32_t(timer::info::irq));
524   -
525   - init();
526   - }
527   -
528   - static constexpr uint32_t ticks_per_usec()
529   - {
530   - // NOTE: we will be using the fastest clock for TC ticks
531   - // just using a prescaler of 2
532   - return
533   - static_cast<uint32_t>( ((VARIANT_MCK)>>1)/1000000 );
534   - }
535   -
536   - static constexpr uint32_t max_period() // usecs.
537   - {
538   - return
539   - static_cast<uint32_t>(static_cast<long long>(1<<32)-1) /
540   - ticks_per_usec();
541   - }
542   -
543   - uint32_t period; // usecs.
544   - uint32_t rc; // timer ticks
545   -
546   - callback_t callback;
547   - void* user_ctx;
548   - };
549   -
550   - static _action_ctx_ _ctx_;
  469 + action& operator=(const action&) = delete;
  470 + action& operator=(action&&) = delete;
  471 +
  472 + bool start(
  473 + uint32_t the_period, // hundreths of usecs. (1e-8 secs.)
  474 + callback_t the_callback,
  475 + void* the_user_ctx
  476 + )
  477 + { return _ctx_.start(the_period,the_callback,the_user_ctx); }
  478 +
  479 + void stop() { _ctx_.stop(); }
  480 +
  481 + void lock() { timer::disable_tc_interrupts(); }
  482 + void unlock() { timer::enable_tc_interrupts(); }
  483 +
  484 + constexpr uint32_t max_period() // hundreths of usecs.
  485 + { return _ctx_.max_period(); }
  486 +
  487 + // NOTE: get_period() returns 0 if the action is stopped
  488 + uint32_t get_period() // hundreths of usecs. (1e-8 secs.)
  489 + { return _ctx_.period; }
  490 +
  491 + uint32_t get_ticks()
  492 + { return _ctx_.ticks(_ctx_.period); }
  493 +
  494 + constexpr uint32_t ticks(uint32_t period)
  495 + { return _ctx_.ticks(period); }
  496 +
  497 + static void tc_interrupt(uint32_t the_status)
  498 + { _ctx_.tc_interrupt(the_status); }
  499 +
  500 + using timer = tc_core<TIMER>;
  501 +
  502 + private:
  503 +
  504 + struct _action_ctx_
  505 + {
  506 +
  507 + _action_ctx_() { init(); }
  508 +
  509 + void init()
  510 + { period=0; callback=[](void* dummy){}; user_ctx=nullptr; }
  511 +
  512 + void tc_interrupt(uint32_t the_status)
  513 + {
  514 + // RC compare interrupt
  515 + if(
  516 + (the_status & TC_SR_CPCS) &&
  517 + timer::is_enabled_rc_interrupt()
  518 + ) { callback(user_ctx); }
  519 + }
  520 +
  521 + bool start(
  522 + uint32_t the_period,
  523 + callback_t the_callback,
  524 + void* user_ctx
  525 + );
  526 +
  527 + void stop()
  528 + {
  529 + timer::disable_rc_interrupt();
  530 +
  531 + timer::stop_interrupts();
  532 + pmc_disable_periph_clk(
  533 + static_cast<uint32_t>(timer::info::irq)
  534 + );
  535 +
  536 + init();
  537 + }
  538 +
  539 + static constexpr uint32_t ticks(
  540 + uint32_t period // hundreths of usecs (1e-8 secs.)
  541 + )
  542 + {
  543 + // NOTE: we will be using the fastest clock for TC ticks
  544 + // just using a prescaler of 2
  545 + return
  546 + static_cast<uint32_t>(
  547 + static_cast<long long>(period)
  548 + * static_cast<long long>(VARIANT_MCK>>1)
  549 + / static_cast<long long>(100000000)
  550 + );
  551 + }
  552 +
  553 + static constexpr uint32_t ticks_per_usec()
  554 + { return ticks(100); }
  555 +
  556 + static constexpr uint32_t max_period() // hundreths of usecs.
  557 + {
  558 + return static_cast<uint32_t>(
  559 + static_cast<long long>(1<<32)-static_cast<long long>(1)
  560 + );
  561 + }
  562 +
  563 + uint32_t period; // usecs.
  564 + uint32_t rc; // timer ticks
  565 +
  566 + callback_t callback;
  567 + void* user_ctx;
  568 + };
  569 +
  570 + static _action_ctx_ _ctx_;
551 571 };
552 572  
553 573 template<timer_ids TIMER>
... ... @@ -555,7 +575,7 @@ namespace arduino_due
555 575  
556 576 template<timer_ids TIMER>
557 577 bool action<TIMER>::_action_ctx_::start(
558   - uint32_t the_period,
  578 + uint32_t the_period, // hundreths of usecs. (1e-8 secs.)
559 579 callback_t the_callback,
560 580 void* the_user_ctx
561 581 )
... ... @@ -567,7 +587,7 @@ namespace arduino_due
567 587 user_ctx=the_user_ctx;
568 588  
569 589 // period in timer ticks
570   - rc=period*ticks_per_usec();
  590 + rc=ticks(period);
571 591  
572 592 // PMC settings
573 593 pmc_set_writeprotect(0);
... ... @@ -579,7 +599,7 @@ namespace arduino_due
579 599 timer::info::channel,
580 600 TC_CMR_TCCLKS_TIMER_CLOCK1 | // clock prescaler set to /2
581 601 TC_CMR_CPCTRG | // timer reset on RC match
582   - TC_CMR_ETRGEDG_NONE // no external trigger
  602 + TC_CMR_ETRGEDG_NONE // no external trigger
583 603 );
584 604  
585 605 // seting RC to the given period
... ...