Author: Doug Paradis
This article discusses how to connect the L298 motor driver in three modes: drive/coast, sign-magnitude, and lock anti-phase. Code examples will be for the Arduino Uno (or with small modifications the Mega2560).
The L298N is a dual H-bridge chip often packaged nicely on a PCB module. It is widely used on small inexpensive hobbyist robots. It has a maximum current specification of 2.0 A per channel with a peak current of 3.0 A per channel (from STI spec sheet). Each H-bridge can control one DC brushed motor.
Picture of a common L298N PCB module
The L298N integrated circuit surrounds the four transistor H-bridge with control circuitry that makes it easy to use and protects the H-bridge from damage such as shoot-through. The L298N uses NPN bipolar transistors for the H-bridge. The symbolic circuit for one of the L298N’s two H-bridges is shown below and will be used for the rest of the article.
The Inputs / Output logic table for the L298N:
PIN | Forward | Reverse | Coast | Brake |
IN1 (input 1) | HIGH | LOW | LOW or HIGH | Same as IN2 |
IN2 (input 2) | LOW | HIGH | LOW or HIGH | Same as IN1 |
ENA (enable A) | HIGH | HIGH | LOW | HIGH |
Drive/Coast Mode
The Drive/Coast Mode is the most common found connection method for the L298N when searching the internet on how to use the L298N on small robots. It is a variation of sign-magnitude and is called by many names. This mode alternates between driving the motor and disenabling the H-bridge (coasting). It connects the two inputs of the H-bridge to General Purpose Input/Output pins (GPIO) and the enable pin to a pulse width modulated pin (PWM).
Table of pin connections:
PIN | TYPE OF CONNECTION | Purpose |
IN1 (input 1) | GPIO | Set Direction |
IN2 (input 2) | GPIO | Set Direction |
ENA (enable A) | PWM | Modulate Speed |
Since ENA is using a PWM signal, the L289N will alternate between Forward (or reverse) and Coast columns of the L298N logic table. Motor speed is determined by the modulation value of the PWM pin. Below shows the current path for the two Enable pin states when moving forward.
Current path when PWM on enable pin is HIGH in Forward direction.
Current path when PWM on enable pin is LOW (all 4 H-bridge transistors are off).
To reverse the motor’s direction the 2 input pin’s values are reversed. The motor current flows as shown below when the Enable pin is high. When the Enable pin is low, the H-bridge state is the same as for the forward direction (i.e., all four H-bridge transistors off).
Current path when PWM on enable pin is HIGH in Reverse direction.
It is possible to brake stop the motor in the Drive/Coast mode, by setting the two inputs to the same state (either LOW or HIGH) and having the enable pin high. For a robot, a coast stop can cause the robot’s momentum to overshoot a desired stop location. To correct for this, braking can be applied when the deacceleration is above a given value or if the controller calls for a zero speed. Using LOW on both inputs, and setting enable HIGH, turns on transistors Q2 and Q4, shorting the motor through the lower transistors of the H-bridge. Using HIGH on both inputs and enable turns on transistors Q1 and Q3, shorting the motor through the upper transistors of the H-bridge.
Current path when Braking through the lower transistors.
Arduino code example code for Drive/Coast mode on L298N.
/*******************************************************************************
-- Motor Test (drive/coast version) --
Program cycles through the following sequence:
1. Motor runs in forward direction for 2 seconds.
2. Motor brake stops for 2 seconds.
3. Motor runs in reverse direction for 2 seconds.
4. Motor coast stops for 2 seconds.
Sequence repeats.
Routines use drive/coast mode to drive L298N H-Bridge module (common on small robots).
Input 1: IN1, pin A0
Input 2: IN2, pin A1
Enable: ENA, pin 5
Differences in stop methods will be minimum for no or light load conditions.
Motor leads may need to be reversed to obtain proper direction.
Program tested on Arduino Uno.
Written by Doug Paradis 1/5/2021
*******************************************************************************/
// define pins for the motor driver board (note: Enable pin not jumpered)
#define PIN_IN1 A0 // GPIO
#define PIN_IN2 A1 // GPIO
#define PIN_ENA_PWM 5 // must be PWM capable pin
void set_mtr_speed(int16_t speed); // function prototype
void brake(); // function prototype
void setup()
{
// set pin types for motor driver board
pinMode(PIN_IN1,OUTPUT); // Define pin 14 for output (IN0)
pinMode(PIN_IN2,OUTPUT); // Define pin 15 for output (IN1)
// In Arduino, you don't need to use pinMode on pins that use PWM (pin 5).
}
void loop()
{
// define stop speed value
const int16_t stop = 0;
// speed value
int16_t spd = 150;
// run motor forward
set_mtr_speed(spd);
delay(2000);
// brake stop
brake();
delay(2000);
// run motor in reverse
set_mtr_speed(-spd);
delay(2000);;
// stop motor
set_mtr_speed(stop);
delay(2000);
}
//-------------- functions -------------------------------------
// Set speed for left motor (looking from rear - speed range is -255 to 255)
void set_mtr_speed(int16_t speed)
{
uint8_t direct = 0; // forward
if (speed < 0){
direct = 1; // reverse
}
switch (direct) {
case 0: // forward
digitalWrite(PIN_IN1, HIGH);
digitalWrite(PIN_IN2, LOW);
analogWrite(PIN_ENA_PWM, speed);
break;
case 1: // reverse
digitalWrite(PIN_IN1, LOW);
digitalWrite(PIN_IN2, HIGH);
analogWrite(PIN_ENA_PWM, -speed);
break;
}
}
void brake()
{
int16_t full_on = 255;
digitalWrite(PIN_IN1, LOW);
digitalWrite(PIN_IN2,LOW);
analogWrite(PIN_ENA_PWM, full_on);
}
A concern is that during the coast portion of this mode all 4 transistors are turned off. The inductance in the motor will not allow current to go to zero instantaneously. The voltage will rise to allow the current to flow, which must go somewhere, and one possible path is through the catch diodes.
Sign-Magnitude Mode
The sign-magnitude uses only one GPIO Pin and one PWM pin per H-bridge. The GPiO and PWM pins are connected to the inputs and the enable pin is tied HIGH by a jumper. In this mode, the H-bridge is alternating between going forward (or reverse) and braking. An advantage of the sign-magnitude mode is that it uses one less GPIO pin than the Coast/Break stop mode. It also continuously applies braking.
Table of pin connections:
PIN | TYPE OF CONNECTION | Purpose |
IN1 (input 1) | GPIO | Set Direction |
IN2 (input 2) | PWM | Modulate Speed |
ENA (enable A) | Jumper HIGH | – |
The transistor states for the PWM modulation are below:
Note that for a given direction, the Side A transistors are set, and the Side B are modulated.
Arduino code example code for Sign-Magnitude mode on L298N.
/*******************************************************************************
-- Motor Test (sign magnitude version) --
Code for "Build More Robots"
Program cycles through the following sequence:
1. Motor runs in forward direction for 2 seconds.
2. Motor runs in reverse direction for 2 seconds.
3. Motor stops for 2 seconds.
Sequence repeats.
Routines use Sign Magnitude to drive L298 H-Bridge module (common on small robots).
Input 1: IN1, pin A1, GPIO
Input 2: IN2, pin 5, PWM
Enable: ENA, jumper high
Motor leads may need to be reversed to obtain proper direction.
Program tested on Arduino Uno.
Written by Doug Paradis 1/5/2021
Algorithm provided by David Ackley in DPRG RBNV 12/29/2020
- Use the sign bit of the speed variable to drive one of the motor's INx inputs.
- Use the bottom bits of the speed variable as PWM input value to drive the
other INx input.
The inversion of bits on a negative number handles the PWM value required by
negative speed values without additional coding.
Example:
Note: Pos speed values go from 1 to 255, neg speed values go from 255 to 1.
Speed = 1, is 0b00000001 (equvalent to INx = 1;)
Speed = -1, is 0b11111111 (equvalent to INx = 256 - 1;)
Speed = 0, is 0b00000000 (INx = 0)
*******************************************************************************/
// define pins for the motor driver board note: enable jumpered
#define PIN_IN1 A0 // Define A0 (14) Pin
#define PIN_IN2 5 // PWM
void setMotorSpeed(int16_t speed); // function prototype
void setup()
{
// set pin types for motor driver board
pinMode(PIN_IN1,OUTPUT); // Define pin 14 for output (IN0)
// In Arduino, you don't need to use pinMode on pins that use PWM
}
void loop()
{
// define stop speed value
const int16_t stop = 0;
// speed value range is -256 to 255
int16_t spd = 75;
// run motor forward
setMotorSpeed(spd);
delay(2000);
// run motor in reverse
setMotorSpeed(-spd);
delay(2000);;
// stop motor
setMotorSpeed(stop);
delay(2000);
}
//-------------- functions -------------------------------------
// Set speed for right motor (looking from rear - speed range is -256 to 255)
void setMotorSpeed(int16_t speed)
{
uint8_t spd_bytes[2];
spd_bytes[0] = (speed >> 8) & 0x01; // strip off direction bit (using 9th bit)
spd_bytes[1] = speed & 0xFF; // obtain speed value from lower bits
digitalWrite(PIN_IN1,spd_bytes[0]); // direction
analogWrite(PIN_IN2,spd_bytes[1]); // speed value for PWM
}
Lock Anti-phase Mode
Lock Anti-phase mode drives each H-bridge input with a separate PWM pin, one of which is out of phase with the other. The enable pin is tied to HIGH by a jumper. If an external inverter is available, a single PWM can be used to drive the motor along with its inverted signal. Below is an oscilloscope picture of the two inputs in lock anti-phase mode. Motor direction depends on the PWM pins value. If the PWM is less than 50% the motor turns in one direction with maximum speed at near 0% PWM values and slowing to zero speed at ~50% PWM. Above 50% PWM speed increases in the other direction with the maximum speed at near 100%. If you are using the analogWrite function in Arduino, you do not want to run at either 0% or 100% PWM. This is due to how the Arduino analogWrite function is written.
Since the inputs never are at the same value, braking by shorting the motor to ground or the Vcc as in other modes does not occur, however if the back EMF becomes greater than the battery voltage (ex., during deceleration) regenerative braking will occur. Likewise if the back EMF becomes lower than the battery voltage (ex. during acceleration) dynamic braking occurs. In regenerative braking current is sent back into the power supply. In dynamic breaking current is pulled from the power supply. If the power supply cannot handle the “recharging” caused by the regenerative braking, damage could occur (i.e, boom!).
Oscilloscope Trace of the PWM signals on the two inputs of the L298N (note: The traces’ positions have been offset vertically for clarity.).
Table of pin connections:
PIN | TYPE OF CONNECTION | Purpose |
IN1 (input 1) | PWM | Modulate Speed |
IN2 (input 2) | Inverse of PWM on IN1 | Modulate Speed |
ENA (enable A) | Jumper HIGH | – |
The transistor states for the PWM modulation are below:
Arduino code example code for lock anti-phase mode on L298N.
/*******************************************************************************
-- Motor Test (lock anti-phase version) --
Program cycles through the following sequence:
1. Motor runs in forward direction for 2 seconds.
2. Motor runs in reverse direction for 2 seconds.
3. Motor stops for 2 seconds.
Sequence repeats.
Routines use lock anti-phase mode to drive L298 H-Bridge module (common on small robots).
The two inputs for the motor controller are fed a PWM and an inverted PWM signal.
Input 1: IN1, pin 5, PWM signal
Input 2: IN2, pin 6, inverted PWM signal
Enable: ENA, jumper high
Note: The PWM pins must be from the same timer for this to work.
Motor leads may need to be reversed to obtain proper direction.
Program tested on Arduino Uno.
Written by Doug Paradis 1/5/2021
*******************************************************************************/
// define pins for the motor driver board note: enable jumpered
#define PIN_IN1 5 // PWM
#define PIN_IN2 6 // PWM (inverse of signal on pin 5)
void setMotorSpeed (int16_t val); // function prototype
void setup()
{
// In Arduino, you don't need to use pinMode on pins that use PWM
}
void loop()
{
// define stop speed value
const int16_t stop = 0;
// speed value range is -127 to 127
int16_t spd = 75;
// run motor forward
setMotorSpeed(spd);
delay(2000);
// run motor in reverse
setMotorSpeed(-spd);
delay(2000);;
// stop motor
setMotorSpeed(stop);
delay(2000);
}
//-------------- functions -------------------------------------
// Use the two PWM pins from the same timer for each motor.
void setMotorSpeed (int16_t val)
{
// shift speed value from 1 - 254, to -127 to 127
// routine will not work for analogWrite values 0 and 255.
val = map(val, -127, 127, 1, 254);
analogWrite (PIN_IN1, val) ;
analogWrite (PIN_IN2, val) ;
// Use for PWM pins 5 and 6 (timer0 - Uno)
TCCR0A |= (1<<4); // set Com0B2 bit (invert chan B)
// Use for PWM pins 9 and 10 (timer1 - Uno)
//TCCR1A |= (1<<4); // set Com1B2 bit (invert chan B)
// Use for PWM pins 11 and 3 (timer2 - Uno)
//TCCR2A |= (1<<4); // set Com2B2 bit (invert chan B)
}
Final Thoughts
The question for hobby roboticists is which mode should they use? For the small and light robots that typically use the L298N motor driver modules you should not run into problems with any of the modes.
The Drive/Coast mode is the only mode that can do a free running motor stop. It takes an extra pin than the other modes.
The sign-magnitude mode has the advantage of only using two pins per motor. It also is continuously braking, which is often advantageous for small robots. All the L298N PCB modules available from the usual sources have the option of tying the enable pin to high via a jumper. These factors make it a good choice.
The lock anti-phase mode has the potential of only using 1 pin if you have an external inverter. Unfortunately, an external inverter is not generally available, and you end up using 2 PWM pins (one inverted). PWM pins can be a premium on a small microprocessor like the Arduino Uno. This can be a disadvantage if you have many motors on your robot. However, there are many other microprocessor choices available. Lock anti-phase mode can have issues with supply ripple at the PWM frequency.
Regenerative braking can occur in all the modes but should not be an issue with an L298N unless the robot is heavy and changing speeds abruptly.
Adding a large capacitor (at least a few hundred μF rated well above the maximum supply voltage) across the Supply pins (Vcc and GND) can often improve performance by reducing power supply ripple.