Closed Robert-K closed 1 year ago
PWM input is supported on both the input pin and the enable/inhibit pin. However, the behavior is different, because the freewheeling current takes a different path. See page 4 and figure 7 of https://www.st.com/resource/en/application_note/cd00003776-applications-of-monolithic-bridge-drivers-stmicroelectronics.pdf for more details.
I've never really compared the behaviors of both modes, so I can't really tell you whether this is the cause of the issues you're facing.
That said, you shouldn't need to modify too much if you want to switch to a 3-pin drive mode.
What you need to know about the timers is that they generate a rectangular PWM wave on an output pin, the duty cycle of which is set by the value in the Output Compare register (OCRnX, where n is the timer number, and X is the channel, either A or B). The code uses two timers (Timer 0 and Timer 2), and each timer has two channels, A and B. Each channel is hard-wired to a specific pin, e.g. Timer 0 channel A drives pin 6. You can see this on page two of the full pinout: pin D6 is labeled OC0A
(Output Compare of Timer 0, channel A).
Besides OCRnX, another important register bit is the COMnX0 bit (Compare Output Mode for timer n channel X) in the TCCRnA register (Timer/Counter n Control Register A). When set to 1, this bit inverts the output pin. Toggling this bit has the effect of changing the duty cycle to its complement, e.g. from 25% to 75%.
As you probably know, to change the direction of the motor, you need to invert both input pins, i.e.
IN1 | IN2 | EN | |
---|---|---|---|
L | H | H | Forward |
H | L | H | Backward |
H | H | H | Free running stop |
L | L | H | Free running stop |
X | X | L | Faster stop |
The current code does the following to change direction: it inverts the output pin of IN2, and it changes the COMnX0 bit for the IN1 pin. This is done here for forward and backward operation, respectively:
To change this to 3-pin operation, you can do the following. Let's assume the following pinout, and we'll only look at one fader:
Arduino pin | Driver pin |
---|---|
2 (PD2) | IN1 |
3 (PD3/OC2B) | EN |
4 (PD4) | IN2 |
To initialize (Motors::begin()
), we just set all three pins as outputs:
if (Config::num_faders > 0) {
sbi(DDRD, 2); // PD2 output
sbi(DDRD, 3); // PD3/OC2B output
sbi(DDRD, 4); // PD4 output
}
To move in one direction (Motor::forward()
):
else if (Idx == 0)
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
cbi(PORTD, 2); // IN1 low
sbi(PORTD, 4); // IN2 high
OCR2B = speed;
}
And to move in the other (Motor::backward()
):
else if (Idx == 0)
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
sbi(PORTD, 2); // IN1 high
cbi(PORTD, 4); // IN2 low
OCR2B = speed;
}
Note that the COM2B0 bit is no longer used, it is always set to zero, regardless of direction.
Wow! Thanks so much for the detailed answer! I'll see to trying this out as soon as I can! In the meantime, I'll also order some L293Ds, just in case.. they are truly cheap :D Thanks again, I'll report back when I get some results 👍
Success!!! It's buttery smooth now, apparently, the L298N should only receive pwm signals on it's ENA pin.. The code you provided worked on first try! Really a simple change, thanks to your great design :) Thank you so much 😊
The L293Ds arrived, got an even smoother operation with them. I recommend any future readers to just use these.
Hey, first of all, thanks for making this amazing project open source!!! ❤️
I got the whole thing set up (single fader, test_reference, serialMIDI etc) and it somewhat works. For touch, I had to use a 1MΩ resistor, everything else was to jittery (even with threshold adjustments). I'm using an Arduino Nano clone with USB-C, but that shouldn't really matter.
Here's the problem though: I'm using an L298N instead of the L293D H-Bridge and the motor movements are not smooth at all.
PIDs seem fine, it's not overshooting or anything, but it makes a rather low frequency stuttering sound and the movements are jerky. I suspect, the L298N doesn't really like pwm on the IN1 and IN2 pins??? I drove the fader with some custom code before and it was smooth, but I used 3 pins, with one dedicated to PWM.
Since the timers for PWM seem pretty complicated to me, I'd rather have my suspicions confirmed/refuted before trying to modify any core code.
Any idea what might be happening there?