Skip to content

Commit

Permalink
Fix timer drifting on AVR platform which introduces flickering when d…
Browse files Browse the repository at this point in the history
…immers are more than 8 (#45)

* improving precision of gate activation on Atmega (needed to control more that 8 dimmers)

* example for avr with 16 dimmers

* fix: stop timer when turning off all the thyristors at the end of the semi-period

* Revert "example for avr with 16 dimmers"

* fix assignment N in DimmableLight class (reverted in previous commit); typo
  • Loading branch information
fabianoriccardi authored Nov 12, 2023
1 parent 50dadf6 commit cee4001
Show file tree
Hide file tree
Showing 4 changed files with 55 additions and 25 deletions.
2 changes: 1 addition & 1 deletion src/dimmable_light.h
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ class DimmableLight {
};

private:
static const uint8_t N = 8;
static const uint8_t N = Thyristor::N;
static uint8_t nLights;

Thyristor thyristor;
Expand Down
36 changes: 26 additions & 10 deletions src/hw_timer_avr.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,8 @@
static void (*timer_callback)() = nullptr;

ISR(TIMER_COMPA_VECTOR(TIMER_ID)) {
// Stop counter
TCCRxB(TIMER_ID) = 0;
// Disable interrupt of Output Compare A
TIMSKx(TIMER_ID) &= 0b11111101;

if (timer_callback != nullptr) { timer_callback(); }
}
Expand Down Expand Up @@ -111,7 +111,8 @@ uint16_t microsecond2Tick(uint16_t micro) {
void timerBegin() {
// clean control registers TCCRxA and TCC2B registers
TCCRxA(TIMER_ID) = 0;
TCCRxB(TIMER_ID) = 0;
// Set CTC mode
TCCRxB(TIMER_ID) = 0x08;

// Reset the counter
// From the AVR datasheet: "To do a 16-bit write, the high byte must be written
Expand All @@ -123,17 +124,14 @@ void timerBegin() {
TCNTxH(TIMER_ID) = 0;
TCNTxL(TIMER_ID) = 0;
#endif

// enable interrupt of Output Compare A
TIMSKx(TIMER_ID) = 1 << OCIExA(TIMER_ID);
}

void timerSetCallback(void (*f)()) {
timer_callback = f;
}

bool timerStartAndTrigger(uint16_t tick) {
if (tick <= 1) { return false; }
void timerStartAndTrigger(uint16_t tick) {
timerStop();

#if N_BIT_TIMER == 8
TCNTx(TIMER_ID) = 0;
Expand All @@ -155,9 +153,27 @@ bool timerStartAndTrigger(uint16_t tick) {
TCCRxB(TIMER_ID) = 0x07;
#elif N_BIT_TIMER == 16
// 0x02: start counter with prescaler 8
TCCRxB(TIMER_ID) = 0x02;
TCCRxB(TIMER_ID) |= 0x02;
#endif
return true;

// enable interrupt of Output Compare A
TIMSKx(TIMER_ID) = 1 << OCIExA(TIMER_ID);
}

void timerSetAlarm(uint16_t tick) {
#if N_BIT_TIMER == 8
OCRxA(TIMER_ID) = tick;
#elif N_BIT_TIMER == 16
OCRxAH(TIMER_ID) = tick >> 8;
OCRxAL(TIMER_ID) = tick;
#endif

// enable interrupt of Output Compare A
TIMSKx(TIMER_ID) = 1 << OCIExA(TIMER_ID);
}

void timerStop() {
TCCRxB(TIMER_ID) &= 0b11111000;
}

#endif // END AVR
6 changes: 5 additions & 1 deletion src/hw_timer_avr.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,11 @@ void timerSetCallback(void (*f)());
*
* NOTE: 0 or 1 values are not accepted
*/
bool timerStartAndTrigger(uint16_t tick);
void timerStartAndTrigger(uint16_t tick);

void timerSetAlarm(uint16_t tick);

void timerStop();

#endif // HW_TIMER_ARDUINO_H

Expand Down
36 changes: 23 additions & 13 deletions src/thyristor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,10 @@ void turn_off_gates_int() {
for (int i = alwaysOnCounter; i < Thyristor::nThyristors; i++) {
digitalWrite(pinDelay[i].pin, LOW);
}

#if defined(ARDUINO_ARCH_AVR)
timerStop();
#endif
}

/**
Expand Down Expand Up @@ -173,8 +177,8 @@ void activate_thyristors() {
digitalWrite(pinDelay[thyristorManaged].pin, HIGH);
thyristorManaged++;

// This while is dedicated to all those thyristor wih delay == semiPeriodLength-margin; those are
// the ones who shouldn't turn on, hence they can be skipped
// This while is dedicated to all those thyristors with delay == semiPeriodLength-margin; those
// are the ones who shouldn't turn on, hence they can be skipped
while (thyristorManaged < Thyristor::nThyristors && pinDelay[thyristorManaged].delay == semiPeriodLength) {
thyristorManaged++;
}
Expand All @@ -197,9 +201,7 @@ void activate_thyristors() {
#elif defined(ARDUINO_ARCH_ESP32)
setAlarm(delayAbsolute);
#elif defined(ARDUINO_ARCH_AVR)
if (!timerStartAndTrigger(microsecond2Tick(delayRelative))) {
Serial.println("activate_thyristors() error timer");
}
timerSetAlarm(microsecond2Tick(delayRelative));
#elif defined(ARDUINO_ARCH_SAMD)
timerStart(microsecond2Tick(delayRelative));
#endif
Expand Down Expand Up @@ -232,9 +234,7 @@ void activate_thyristors() {
setAlarm(delayAbsolute);
#elif defined(ARDUINO_ARCH_AVR)
timerSetCallback(turn_off_gates_int);
if (!timerStartAndTrigger(microsecond2Tick(delayRelative))) {
Serial.println("activate_thyristors() error timer");
}
timerSetAlarm(microsecond2Tick(delayRelative));
#elif defined(ARDUINO_ARCH_SAMD)
timerSetCallback(turn_off_gates_int);
timerStart(microsecond2Tick(delayRelative));
Expand Down Expand Up @@ -299,6 +299,16 @@ void zero_cross_int() {
if (diff < semiPeriodLength - semiPeriodShrinkMargin) { return; }
#endif

#endif

#if defined(ARDUINO_ARCH_AVR)
// Early timer start, only for avr. This is necessary since the instructions executed in this
// ISR take much time (more than 30us with only 4 dimmers). Before the end of this ISR, either
// the timer is stop or the alarm time is properly set.
timerStartAndTrigger(microsecond2Tick(15000));
#endif

#if defined(FILTER_INT_PERIOD) || defined(MONITOR_FREQUENCY)
#ifdef MONITOR_FREQUENCY
// if diff is very very greater than the theoretical value, the electrical signal
// can be considered as lost for a while and I must reset my moving average.
Expand Down Expand Up @@ -424,9 +434,7 @@ void zero_cross_int() {
startTimerAndTrigger(delayAbsolute);
#elif defined(ARDUINO_ARCH_AVR)
timerSetCallback(activate_thyristors);
if (!timerStartAndTrigger(microsecond2Tick(delayAbsolute))) {
Serial.println("zero_cross_int() error timer");
}
timerSetAlarm(microsecond2Tick(delayAbsolute));
#elif defined(ARDUINO_ARCH_SAMD)
timerSetCallback(activate_thyristors);
timerStart(microsecond2Tick(delayAbsolute));
Expand All @@ -445,8 +453,10 @@ void zero_cross_int() {
// and no-autorealod was set (this timer can only down-count).
#elif defined(ARDUINO_ARCH_ESP32)
stopTimer();
#elif defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_ARCH_SAMD)
// Given actual HAL, AVR and SAMD counter automatically stops on interrupt
#elif defined(ARDUINO_ARCH_AVR)
timerStop();
#elif defined(ARDUINO_ARCH_SAMD)
// Given actual HAL, and SAMD counter automatically stops on interrupt
#endif
}
}
Expand Down

0 comments on commit cee4001

Please sign in to comment.