analogWriteFrequency() causes glitches output

hudson

Member
24521158202_da6ca965e0_z_d.jpg
Is there a way to avoid glitches caused by changing the output frequency with analogWriteFrequency()? It appears to force a reset of the counter when it is called, which causes a transition earlier than it should. In this example the same frequency value is written (when trace 2 goes high), so the square wave should be constant, but instead it has a truncated pulse on the PWM output.

Code:
void setup()
{
  pinMode(10, OUTPUT);
  pinMode(13, OUTPUT);
}

void loop()
{
  analogWriteFrequency(10, 666);
  analogWrite(10, 128);

  digitalWrite(13, 1);
  delay(90);
  digitalWrite(13, 0);
  delay(10);
}
 
The offending code appears to be in pins_teensy.c:
Code:
        } else if (pin == 5 || pin == 6 || pin == 9 || pin == 10 ||
          (pin >= 20 && pin <= 23)) {
                FTM0_SC = 0;
                FTM0_CNT = 0;
                FTM0_MOD = mod;
                FTM0_SC = FTM_SC_CLKS(1) | FTM_SC_PS(prescale);
        }

Is it necessary to set FTM0_CNT=0 for a reason that I'm missing?
 
I believe it was done this way based on these words from section 36.3.5 from the reference manual.

Initialize the FTM counter, by writing to CNT, before writing to the MOD register to
avoid confusion about when the first counter overflow will occur.

However, reading the rest of 36.3.5 and 36.4.10.2, it looks like that's not really necessary. But if you write a new MOD value that's smaller, at a moment when the current count is equal or greater, then you can end up the counter going all the way to 0xFFFF before wrapping over to 0. Or in other words, it looks like the hardware only checks equals, not greater-than, and the counter increments.

I appreciate your effort to make this a small, very reproducible example. But for real-world use, are you changing the frequency? In other words, just reading the MOD value and doing nothing would fix this example, but do nothing for a real usage that's actually calling analogWriteFrequency() to change the setting.
 
Yes, the example is quite simplified -- I'm using the PWM output to drive a stepper motor and controlling the velocity with the frequency. The occasional short pulses were causing the stepper to skip steps at certain speeds.

I'll copy the code out of analogWriteFrequency() into my own routine and have it check FTM0_CNT after writing to FTM0_MOD to see if it needs to force a reset when adjusting the frequency. This will cause a mid-length pulse during the transition, which is acceptable. Thanks for the clarification!
 
Hello Hudson, I am interested by your attempt to modify analogWriteFrequency so that there is no glitch when it is called. Did you succeed ?
 
Hello Paul,
I am wondering why you say that "But if you write a new MOD value that's smaller, at a moment when the current count is equal or greater, then you can end up the counter going all the way to 0xFFFF before wrapping over to 0.*» since 36.4.10.2 says «*If the selected mode is not CPWM then MOD register is updated after MOD register was written and the FTM counter changes from MOD to CNTIN*».
What do you think ?
 
Back
Top