L298N Motor Driver with Arduino

1. Key Features of the L298N

1.1 Key Features of the L298N

Dual H-Bridge Configuration

The L298N integrates two independent H-bridge circuits, enabling bidirectional control of two DC motors or a single stepper motor. Each H-bridge consists of four power transistors arranged in a bridge topology, allowing current to flow in either direction through the motor windings. The switching logic follows the truth table:

$$ \begin{cases} IN1 = HIGH, IN2 = LOW \Rightarrow \text{Forward rotation} \\ IN1 = LOW, IN2 = HIGH \Rightarrow \text{Reverse rotation} \\ IN1 = IN2 \Rightarrow \text{Fast motor stop (short brake)} \end{cases} $$

Voltage and Current Specifications

The driver supports a wide operating voltage range of 4.5V to 46V DC, with a peak current capability of 2A per channel (3A momentary). The maximum power dissipation is given by:

$$ P_{max} = (V_{in} - V_{sat}) \times I_{load} $$

where Vsat represents the saturation voltage (~2V typical) across the power transistors. For thermal management, the chip requires an external heatsink when operating above 1A continuous current.

PWM Speed Control

Each bridge features enable pins (ENA, ENB) that accept pulse-width modulation signals for variable speed control. The effective output voltage follows:

$$ V_{eff} = V_{supply} \times \frac{t_{on}}{T_{period}} $$

where ton is the active high time and Tperiod is the PWM cycle duration. Frequencies between 5kHz-20kHz optimize between switching losses and audible noise.

Built-in Protection Circuits

Logic-Level Compatibility

The control inputs (IN1-IN4) feature TTL/CMOS compatibility with 1.5V logic thresholds, allowing direct interfacing with 3.3V or 5V microcontrollers. Input impedance exceeds 100kΩ, minimizing GPIO current draw.

L298N Functional Diagram H-Bridge 1 H-Bridge 2
L298N H-Bridge Operation with PWM Timing A schematic diagram showing two H-bridge circuits with corresponding PWM timing diagrams, illustrating motor control logic and current flow. L298N H-Bridge Operation with PWM Timing H-Bridge 1 M IN1 IN2 ENA H-Bridge 2 M IN3 IN4 ENB ENA PWM ENB PWM IN1: HIGH IN2: LOW IN3: LOW IN4: HIGH
Diagram Description: The H-bridge configuration and PWM signal timing relationships are inherently spatial concepts that benefit from visual representation.

1.2 Typical Applications

Robotics and Motion Control Systems

The L298N is widely employed in robotics for driving DC motors, stepper motors, and linear actuators. Its dual H-bridge configuration allows bidirectional control, making it ideal for differential drive robots. The motor driver can handle peak currents up to 2A per channel (with proper heat sinking), enabling precise torque control in robotic arms and mobile platforms. Advanced applications include:

Industrial Automation

In industrial settings, the L298N interfaces with PLCs or microcontrollers to drive conveyor belts, sorting mechanisms, and valve actuators. The driver's enable pins allow PWM-based speed regulation, while its freewheeling diodes protect against back-EMF from inductive loads. Key implementations include:

Energy-Efficient Mobility Systems

Electric vehicles and drones utilize the L298N for low-power traction systems. The driver's efficiency (η) can be derived from its voltage drop (VCE(sat)) and load current (IL):

$$ \eta = \frac{P_{out}}{P_{in}} = \frac{V_{supply} - 2V_{CE(sat)}}{V_{supply}} \times 100\% $$

For a 12V system with 1.5V saturation loss per transistor, η ≈ 75%. Practical optimizations include:

Research and Prototyping

Physics experiments often use the L298N for precision motion stages. A common application is driving voice coil actuators in optics benches, where the relationship between PWM duty cycle (D) and force (F) follows:

$$ F = k_t \left( \frac{D \times V_{supply}}{R_{coil}} \right) $$

where kt is the motor constant and Rcoil the winding resistance. This linearity enables nanometer-scale positioning when paired with interferometric feedback.

L298N in H-Bridge Configuration IN1: PWM Input IN2: Direction
L298N H-Bridge Operation with PWM Control Schematic of L298N H-bridge motor driver showing transistor switching, PWM input signals, current paths, and freewheeling diodes. Q1 Q2 Q3 Q4 M +Vs GND Forward Current IN1 (PWM) IN2 (Dir) VCE(sat) Dead Time Back-EMF Regenerative Path
Diagram Description: The section includes mathematical relationships (efficiency and force equations) and H-bridge operation that benefit from visual representation of circuit paths and signal flow.

1.3 Pin Configuration and Functions

Power Supply Pins

The L298N motor driver features three critical power supply pins: VCC, VSS, and GND. The VCC pin (typically labeled as +12V) supplies power to the motor, with an operational range of 5V to 35V. The VSS pin (often +5V) powers the internal logic circuitry, accepting 5V to 7V. A common mistake is reverse-biasing these pins, leading to improper H-bridge operation or thermal damage. The GND pin must be connected to both the Arduino and the power supply ground to ensure a common reference potential.

Motor Output Pins

Two pairs of output pins, OUT1/OUT2 and OUT3/OUT4, drive the connected DC motors or one bipolar stepper motor. These pins are internally connected to the H-bridge transistors, capable of sourcing or sinking up to 2A per channel (peak). The output voltage equals VCC minus the H-bridge voltage drop, typically 1.5V to 2.5V due to Darlington transistor saturation. For a motor rated at 12V, the effective output voltage at full load is approximately 10V.

Control Input Pins

The IN1 to IN4 pins receive TTL/CMOS logic signals from the Arduino to control motor direction and PWM speed. A truth table governs the H-bridge states:

$$ \text{IN1} = \text{HIGH}, \text{IN2} = \text{LOW} \Rightarrow \text{Motor Forward} $$ $$ \text{IN1} = \text{LOW}, \text{IN2} = \text{HIGH} \Rightarrow \text{Motor Reverse} $$

PWM signals applied to IN1/IN2 or IN3/IN4 modulate the average output voltage, controlling motor speed. The L298N's internal diodes clamp back-EMF spikes during switching transients, protecting the H-bridge.

Enable and Current Sensing Pins

The ENA and ENB pins enable or disable the H-bridge channels. Pulling these pins LOW forces the outputs into a high-impedance state, useful for emergency braking. The current sensing pins (SenseA/SenseB) allow external shunt resistors for real-time current monitoring. The voltage drop across the shunt resistor (Rshunt) relates to motor current (Imotor) by:

$$ I_{\text{motor}} = \frac{V_{\text{sense}}}{R_{\text{shunt}}} $$

For a 0.5Ω shunt resistor, a 100mV reading corresponds to 200mA of motor current.

Thermal Considerations

The L298N dissipates power as heat during operation, given by:

$$ P_{\text{dissipated}} = I_{\text{motor}}^2 \times R_{\text{DS(on)}} + V_{\text{CE(sat)}} \times I_{\text{motor}} $$

where RDS(on) is the ON-state resistance (~3Ω per transistor) and VCE(sat) is the saturation voltage (~2V). A heatsink is mandatory for continuous operation above 500mA per channel.

L298N Pinout Diagram with Functional Zones A top-down view of the L298N motor driver IC with color-coded functional zones showing power pins, motor outputs, control inputs, enable pins, and current sense pins. Power Supply Control Inputs Enable Current Sense Motor Outputs VCC +5V VSS +7-46V GND 0V IN1 IN2 IN3 IN4 ENA ENB SenseA SenseB OUT1 2A max OUT2 2A max OUT3 2A max OUT4 2A max
Diagram Description: The diagram would physically show the spatial arrangement of all pin types (power, motor outputs, control inputs, enable/sensing) on the L298N IC and their functional grouping.

2. Required Components and Tools

2.1 Required Components and Tools

Core Electronic Components

The L298N motor driver module operates as a dual H-bridge capable of driving inductive loads such as DC motors and stepper motors. The following components are essential for interfacing it with an Arduino:

Supporting Circuit Elements

Additional passive and active components enhance stability and protect the system:

Measurement and Debugging Tools

Advanced users should equip themselves with the following instrumentation:

Mathematical Considerations

The power dissipation in the L298N can be modeled as:

$$ P_{diss} = I^2 R_{DS(on)} + V_{CE} I_{leakage} $$

where RDS(on) (0.3Ω typical per channel) dominates losses during conduction. For a motor drawing 1A, this results in 0.3W of heat per enabled H-bridge.

Software Requirements

Wiring the L298N to Arduino

Power Supply Configuration

The L298N motor driver requires two distinct voltage inputs: a logic-level supply (Vss) for internal circuitry and a higher-voltage supply (Vs) for motor power. The logic supply (5V) can be sourced from the Arduino's 5V pin, while the motor supply (7–12V) must be provided externally. The driver's onboard 5V regulator can be enabled by shorting the +5V Enable jumper, but this should be avoided if the motor supply exceeds 12V to prevent regulator overheating.

Motor Output Connections

Each L298N channel drives one motor via output pairs (OUT1/OUT2 and OUT3/OUT4). For bidirectional control, motors connect directly to these terminals. The driver's internal H-bridge topology allows current reversal, governed by the truth table below:

$$ \begin{array}{|c|c|c|} \hline \text{IN1} & \text{IN2} & \text{Motor Action} \\ \hline 0 & 0 & \text{Fast Decay (Coast)} \\ 0 & 1 & \text{Reverse} \\ 1 & 0 & \text{Forward} \\ 1 & 1 & \text{Slow Decay (Brake)} \\ \hline \end{array} $$

Arduino GPIO Interface

Connect the L298N's input pins (IN1–IN4) to Arduino PWM-capable GPIOs (e.g., pins 3, 5, 6, 9, 10, or 11) to enable speed control via pulse-width modulation. For a two-motor setup, typical pin assignments are:

The enable pins (ENA and ENB) must be driven high (either by jumper or Arduino GPIO) to activate the respective H-bridge channels. PWM signals applied to these pins modulate motor speed, with duty cycle D relating to output voltage as:

$$ V_{\text{out}} = D \times V_s $$

Current Sensing and Protection

The L298N's sense pins (SenseA and SenseB) allow current monitoring via external shunt resistors. For a 0.5Ω shunt, the current I is derived from the voltage drop Vsense as:

$$ I = \frac{V_{\text{sense}}}{0.5} $$

Always include freewheeling diodes (1N5819 or equivalent) across motor terminals to suppress back-EMF transients, which can exceed 100V during abrupt deceleration.

L298N to Arduino Wiring Diagram Schematic diagram showing wiring connections between an Arduino, L298N motor driver, external power supply, and two DC motors. Includes labeled pins and color-coded wires. Arduino 5V GND D9 D8 D7 D6 L298N Vs Vss GND IN1 IN2 IN3 IN4 OUT1 OUT2 OUT3 OUT4 ENA ENB Power 7-12V DC Motor A Motor B Legend 5V Power Motor Power Ground Control Signals Optional Power
Diagram Description: The diagram would physically show the wiring connections between the L298N and Arduino, including power supply configuration and motor output connections.

2.3 Power Supply Considerations

Voltage and Current Requirements

The L298N motor driver operates within a supply voltage range of 5V to 35V, making it suitable for a variety of DC and stepper motors. However, the driver's internal voltage drop (~2.5V per channel) must be accounted for when selecting the supply voltage. For a motor rated at 12V, the supply should be at least 14.5V to ensure full performance. The driver can deliver a continuous current of 2A per channel (peak 3A), but thermal dissipation becomes critical at higher currents.

$$ V_{supply} = V_{motor} + 2 \times V_{drop} $$

Power Dissipation and Heat Management

Power dissipation in the L298N is governed by the current (I) and the saturation voltage (VCE(sat)) of its internal Darlington transistors. The total power dissipated (Pdiss) for one channel is:

$$ P_{diss} = I^2 \times R_{on} + I \times V_{drop} $$

For a 2A load with Ron ≈ 1.2Ω and Vdrop ≈ 2.5V, this results in ~7.4W per channel. A heatsink is mandatory for sustained operation above 1A per channel to prevent thermal shutdown (Tj > 150°C).

Logic vs. Motor Power Isolation

The L298N requires two separate power inputs:

Decoupling capacitors (100µF electrolytic + 100nF ceramic) should be placed near the motor supply pins to mitigate inductive kickback from the motor coils.

Current Sensing and Limiting

The L298N includes sense pins (Sense A and Sense B) for each H-bridge, enabling external current monitoring via shunt resistors. The voltage drop across the shunt (Vsense) is proportional to the motor current:

$$ I_{motor} = \frac{V_{sense}}{R_{shunt}} $$

For precise control, integrate these signals with an Arduino ADC and implement software-based current limiting to prevent stall conditions.

Practical Implementation Notes

L298N Power Isolation and Current Sensing Setup Schematic diagram showing L298N motor driver with Arduino, highlighting power isolation and current sensing paths. Logic Power Domain Motor Power Domain Arduino 5V GND PWM L298N 5V GND IN1 IN2 VS GND OUT1 OUT2 Motor PSU + - M 0.1µF Rshunt Rshunt Sense A Sense B
Diagram Description: The section covers power isolation and current sensing, which involve spatial relationships between components and signal paths.

3. Basic Motor Control Code

3.1 Basic Motor Control Code

The L298N motor driver operates as a dual H-bridge, enabling bidirectional control of two DC motors or a single stepper motor. The H-bridge topology allows voltage polarity reversal across the motor terminals, facilitating forward and reverse motion. The driver's logic inputs (IN1, IN2, IN3, IN4) determine the output state of each bridge, while enable pins (ENA, ENB) provide PWM-based speed control.

Hardware Configuration

For a single DC motor, connect IN1 and IN2 to Arduino digital pins (e.g., D8, D9), and ENA to a PWM-capable pin (e.g., D10). The motor terminals attach to OUT1 and OUT2, with the L298N's power supply (VCC) set to the motor's rated voltage (typically 5–35V). A separate 5V logic supply powers the Arduino and L298N's internal logic.

Mathematical Basis for PWM Speed Control

The motor's average voltage Vavg is governed by the PWM duty cycle D:

$$ V_{avg} = D \times V_{CC} $$

where D ∈ [0, 1]. The motor's angular velocity ω approximates:

$$ \omega \propto V_{avg} - V_{back-EMF} $$

Back-EMF (Vback-EMF) arises from the motor's rotational motion and opposes the applied voltage, scaling linearly with speed.

Arduino Code Implementation

The following code demonstrates bidirectional control with PWM speed modulation:


// Pin definitions
const int ENA = 10;  // PWM-enabled pin
const int IN1 = 8;   // Direction control pin 1
const int IN2 = 9;   // Direction control pin 2

void setup() {
  pinMode(ENA, OUTPUT);
  pinMode(IN1, OUTPUT);
  pinMode(IN2, OUTPUT);
}

void loop() {
  // Rotate forward at 75% speed
  analogWrite(ENA, 191);  // 191 ≈ 75% of 255 (8-bit PWM)
  digitalWrite(IN1, HIGH);
  digitalWrite(IN2, LOW);
  delay(2000);

  // Brake (short-circuit motor terminals)
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, LOW);
  delay(500);

  // Rotate reverse at 50% speed
  analogWrite(ENA, 127);  // 127 ≈ 50% of 255
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, HIGH);
  delay(2000);

  // Coast (open-circuit motor terminals)
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, LOW);
  analogWrite(ENA, 0);
  delay(500);
}

Key Operational Modes

Current Handling and Protection

The L298N's saturation voltage (VCE(sat)) introduces power dissipation:

$$ P_{diss} = I_{motor} \times V_{CE(sat)} \times 2 $$

where the factor of 2 accounts for two conducting transistors in the H-bridge path. For a 2A motor current and VCE(sat) = 1.8V (typical at 2A), Pdiss ≈ 7.2W per channel, necessitating heatsinking for sustained operation.

Practical Considerations

Flyback diodes (internal to the L298N) suppress inductive voltage spikes during switching transitions. For high-inductance loads, external Schottky diodes may be required to handle peak transient energy. Motor ripple current scales inversely with PWM frequency; frequencies above 20kHz are preferable to minimize audible noise and current ripple.

L298N H-Bridge Operation Modes Schematic diagram of L298N H-bridge operation modes showing current flow paths for forward, reverse, brake, and coast modes. L298N H-Bridge Operation Modes VCC GND Q1 Q2 Q3 Q4 Motor M IN1 IN2 ENA (PWM) Forward Mode (Q1 & Q4 ON)
Diagram Description: The diagram would show the H-bridge topology and current flow paths during different operational modes (forward, reverse, brake, coast).

3.2 Implementing Speed Control with PWM

The L298N motor driver enables precise speed control of DC motors using pulse-width modulation (PWM). The underlying principle relies on varying the duty cycle of a square wave signal to regulate the average voltage delivered to the motor. For an advanced implementation, we must consider both the electrical characteristics of the motor and the timing constraints of the Arduino's PWM hardware.

PWM Fundamentals and Motor Response

The average voltage Vavg delivered to the motor is determined by the duty cycle D of the PWM signal:

$$ V_{avg} = D \times V_{supply} $$

where D ranges from 0 (0% duty cycle, motor stopped) to 1 (100% duty cycle, full speed). The motor's angular velocity ω exhibits a roughly linear relationship with Vavg in its operating range:

$$ \omega \approx k_t \frac{V_{avg} - k_e \omega}{R} $$

where kt is the torque constant, ke is the back-EMF constant, and R is the winding resistance. This first-order approximation holds for steady-state operation below saturation.

Arduino PWM Hardware Implementation

The ATmega328P microcontroller provides three distinct PWM generation modes via its Timer/Counter modules:

For motor control, Fast PWM (Mode 3) typically offers the best compromise between resolution and refresh rate. The PWM frequency fPWM is determined by:

$$ f_{PWM} = \frac{f_{CPU}}{N(1 + TOP)} $$

where N is the prescaler value (1, 8, 64, 256, or 1024) and TOP is typically 0xFF (255) for 8-bit resolution.

L298N Interface Considerations

The L298N's enable pins (ENA, ENB) accept standard TTL-level PWM signals. Key electrical characteristics include:

A practical implementation using Timer1 for 16-bit PWM resolution on Arduino UNO:


#include <avr/io.h>

void setupPWM() {
  // Configure Timer1 for Fast PWM, 10-bit mode
  TCCR1A = (1 << COM1A1) | (1 << WGM11) | (1 << WGM10);
  TCCR1B = (1 << WGM12) | (1 << CS10); // No prescaling
  OCR1A = 512; // 50% duty cycle (10-bit resolution)
  DDRB |= (1 << PB1); // Set OC1A (PB1/D9) as output
}

void setMotorSpeed(uint16_t speed) {
  OCR1A = constrain(speed, 0, 1023); // 10-bit range
}
    

Practical Implementation Notes

When implementing PWM control with the L298N:

The PWM approach provides superior efficiency compared to linear voltage regulation, with typical power dissipation in the L298N given by:

$$ P_{diss} = I^2R_{DS(on)} \times (1 - D) + E_{sw} \times f_{PWM} $$

where RDS(on) is the MOSFET on-resistance (~1.2Ω per channel) and Esw is the switching energy (~50nJ per transition).

PWM Duty Cycle and Motor Voltage Relationship A diagram showing PWM waveforms with varying duty cycles and their corresponding averaged voltage levels driving a motor. Time Voltage D = 25% D = 50% D = 75% V_avg = 25% V_avg = 50% V_avg = 75% M ω ∝ V_avg PWM Period (T)
Diagram Description: The section explains PWM concepts and motor response with mathematical relationships, which would benefit from a visual representation of PWM waveforms and voltage averaging.

3.3 Direction Control Logic

The L298N motor driver operates as an H-bridge, enabling bidirectional control of DC motors by manipulating the logic states of its input pins (IN1, IN2, IN3, IN4). The direction of each motor is determined by the voltage polarity applied across its terminals, governed by the following truth table:

$$ \text{Motor A Direction} = \begin{cases} \text{Forward} & \text{if } \text{IN1} = 1, \text{IN2} = 0 \\ \text{Reverse} & \text{if } \text{IN1} = 0, \text{IN2} = 1 \\ \text{Brake} & \text{if } \text{IN1} = \text{IN2} \\ \text{Coast} & \text{if } \text{IN1} = \text{IN2} = 0 \end{cases} $$

H-Bridge Switching Dynamics

Each half-bridge in the L298N consists of two NPN transistors (or Darlington pairs) in a totem-pole configuration. When IN1 is high and IN2 is low, the upper left and lower right transistors activate, creating a current path from VS (supply voltage) to ground through the motor in one direction. Reversing the logic states flips the polarity.

Dead-Time Consideration

To prevent shoot-through currents during switching transitions, the L298N incorporates a dead-time delay (typically 1–2 µs) between turning off one transistor pair and activating the complementary pair. This is critical for minimizing cross-conduction losses, given by:

$$ P_{\text{loss}} = \frac{1}{2} C_{\text{oss}} V_{\text{DS}}^2 f_{\text{PWM}}} $$

where Coss is the transistor output capacitance, VDS is the drain-source voltage, and fPWM is the switching frequency.

Arduino Implementation

For precise direction control, the Arduino's GPIO pins must interface with the L298N's logic inputs. Below is an optimized code snippet demonstrating dynamic direction switching with PWM speed modulation:


// L298N pin configuration
const int IN1 = 8;  // Motor A direction control
const int IN2 = 9;
const int ENA = 10;  // PWM speed control

void setup() {
  pinMode(IN1, OUTPUT);
  pinMode(IN2, OUTPUT);
  pinMode(ENA, OUTPUT);
}

void loop() {
  // Forward at 75% speed
  digitalWrite(IN1, HIGH);
  digitalWrite(IN2, LOW);
  analogWrite(ENA, 191);  // 191/255 ≈ 75% duty cycle

  delay(2000);

  // Reverse at 50% speed
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, HIGH);
  analogWrite(ENA, 127);  // 127/255 ≈ 50% duty cycle

  delay(2000);
}
    

Practical Considerations

Advanced Applications

For robotic systems requiring microstepping or regenerative braking, the L298N can be paired with an encoder feedback loop. The motor's back-EMF constant (Ke) and torque constant (Kt) become critical parameters:

$$ K_e = \frac{V_{\text{back-EMF}}}{\omega} \quad \text{(in V·s/rad)}} $$ $$ K_t = \frac{\tau}{I} \quad \text{(in N·m/A)}} $$

where ω is angular velocity and τ is torque. In ideal brushed DC motors, Ke ≈ Kt.

L298N H-Bridge Current Paths Schematic diagram of L298N H-bridge showing current paths for motor control with transistors Q1-Q4, logic inputs IN1/IN2, and power supply VS. Color-coded red/blue arrows indicate current direction. M OUT1 OUT2 Q1 Q2 Q3 Q4 VS VS GND GND IN1 IN2 Forward Reverse Shoot-through danger zone
Diagram Description: The H-bridge switching dynamics and current paths are spatial concepts that require visualization of transistor states and motor terminal polarities.

4. Building a Simple Robot Car

4.1 Building a Simple Robot Car

Motor Control Theory

The L298N dual H-bridge motor driver enables bidirectional control of two DC motors or a single stepper motor. Each H-bridge consists of four MOSFETs arranged in a bridge configuration, allowing current to flow in either direction through the motor. The driver's logic operates as follows:

$$ V_{out} = \begin{cases} +V_{supply} & \text{when } IN1 = 1, IN2 = 0 \\ -V_{supply} & \text{when } IN1 = 0, IN2 = 1 \\ 0 & \text{when } IN1 = IN2 \end{cases} $$

Pulse-width modulation (PWM) applied to the enable pins (ENA, ENB) regulates motor speed by varying the duty cycle D:

$$ \omega \propto D = \frac{t_{on}}{T} $$

Hardware Configuration

The robot car requires:

Arduino Firmware Implementation

The control algorithm implements dead-band compensation for motor asymmetry. Below is an optimized implementation with closed-loop speed control:


// L298N pin mapping
const int ENA = 5, ENB = 6;
const int IN1 = 7, IN2 = 8, IN3 = 9, IN4 = 10;

void setMotor(int motor, int speed, bool reverse) {
   speed = constrain(speed, 0, 255);
   if(motor == 1) {
      analogWrite(ENA, speed);
      digitalWrite(IN1, !reverse);
      digitalWrite(IN2, reverse);
   } else {
      analogWrite(ENB, speed);
      digitalWrite(IN3, !reverse);
      digitalWrite(IN4, reverse);
   }
}

void setup() {
   for(int pin=5; pin<=10; pin++) pinMode(pin, OUTPUT);
}
   

Kinematic Model

For a differential drive robot with wheel radius r and track width L, the instantaneous curvature kinematics are:

$$ \begin{bmatrix} v \\ \omega \end{bmatrix} = \begin{bmatrix} \frac{r}{2} & \frac{r}{2} \\ -\frac{r}{L} & \frac{r}{L} \end{bmatrix} \begin{bmatrix} \omega_L \\ \omega_R \end{bmatrix} $$

where ωL and ωR are the left/right wheel angular velocities.

Practical Considerations

L298N Motor Driver Wiring Diagram A schematic diagram showing the wiring connections between an Arduino, L298N motor driver, and DC motors, including PWM and digital control signals. Arduino 5V GND ENA IN1 IN2 IN3 IN4 L298N Module +12V GND +5V ENA IN1 IN2 IN3 IN4 ENB OUT1 OUT2 OUT3 OUT4 Power Supply +12V Motor A Motor B
Diagram Description: The diagram would physically show the wiring connections between the L298N, Arduino, and motors, including PWM and digital control signals.

4.2 Controlling Multiple Motors

The L298N dual H-bridge driver enables independent control of two DC motors or a single bipolar stepper motor. When driving multiple motors, power dissipation and current sharing become critical considerations due to the integrated circuit's thermal limits.

Current Handling and Thermal Constraints

The L298N's maximum current rating per channel is 2A (peak) with a total power dissipation limit of 25W. For continuous operation with two motors, the current I through each H-bridge must satisfy:

$$ I_1 + I_2 \leq 2I_{max} - \Delta I_{thermal} $$

where ΔIthermal accounts for derating due to junction temperature rise. The power dissipation Pd across each bridge is:

$$ P_d = I^2R_{DS(on)} + V_{CE(sat)}I $$

with RDS(on) typically 1.2Ω per switch and VCE(sat) ≈ 1.1V at 1A.

PWM Synchronization Challenges

When using pulse-width modulation (PWM) for speed control, phase-aligned PWM signals minimize current ripple in shared power supplies. The Arduino's analogWrite() function uses timer peripherals with the following constraints:

For precise motor synchronization, modify timer prescalers to match frequencies:


// Set Timer1 for 25kHz PWM on pins 9 & 10
TCCR1A = _BV(COM1A1) | _BV(COM1B1) | _BV(WGM11);
TCCR1B = _BV(WGM13) | _BV(WGM12) | _BV(CS10);
ICR1 = 320; // TOP value for 25kHz with 16MHz clock
  

Back-EMF Protection

During rapid deceleration or load changes, motors generate back-EMF voltages that can exceed the L298N's 46V absolute maximum rating. The time-dependent voltage spike is given by:

$$ V_{spike} = L\frac{di}{dt} + iR + \omega k_e $$

where L is motor inductance, ke the back-EMF constant, and ω angular velocity. Fast recovery diodes (e.g., 1N5822 Schottky) must be installed across each motor terminal with:

Advanced Current Sensing

For closed-loop control, the L298N's current sense pins (SenseA/B) provide voltage drops across 0.5Ω shunt resistors. The sensed voltage Vsense relates to motor current by:

$$ I_{motor} = \frac{V_{sense}}{0.5\Omega} $$

Implement differential amplification with an instrumentation amplifier (e.g., INA219) to improve signal-to-noise ratio. Calibrate readings by accounting for:

L298N Motor Driver M1 M2 M3 M4
L298N PWM Timing and Back-EMF Protection A mixed schematic and timing diagram showing PWM signals from Arduino, L298N driver connections, motor terminals with back-EMF diodes, and current sense pins. PWM Timing Comparison Pins 5/6 (Timer0, 1kHz) Pins 9/10 (Timer1, 500Hz) Pins 3/11 (Timer2, 250Hz) Motor Connections and Protection L298N Driver Motor Back-EMF Diodes Current Sense SenseA/B V_spike
Diagram Description: The section involves PWM synchronization challenges and back-EMF protection, which are highly visual concepts involving timing relationships and voltage spikes.

4.3 Troubleshooting Common Issues

Motor Not Spinning or Responding

If the motor fails to spin, first verify the power supply configuration. The L298N requires a minimum voltage differential between the logic supply (Vss, typically 5V) and the motor supply (Vs, 7-12V). Measure the voltage at the motor output pins (OUT1-OUT4) using an oscilloscope. If the output remains at 0V, check:

Excessive Heat Generation

The L298N's power dissipation follows:

$$ P_d = I^2 R_{DS(on)} + V_{CE} I_{leakage} $$

where RDS(on) is the MOSFET on-resistance (~3Ω per channel). For a 1A load, this results in ~3W of heat per channel. Mitigate by:

Electrical Noise and Voltage Spikes

Back-EMF from inductive loads can induce voltage spikes exceeding 100V. The L298N's internal flyback diodes (1N5819) have a reverse recovery time (~500ns) that may be insufficient for high-di/dt scenarios. Add external Schottky diodes (e.g., MBR0540) in parallel with each motor terminal, with:

$$ V_{RRM} > 2V_{s(max)}, \quad I_F \geq I_{motor(peak)} $$

PWM Frequency Limitations

The L298N's switching speed is constrained by its propagation delay (~2µs). For optimal performance:

Ground Loop Issues

Improper grounding can cause erratic behavior. Implement a star-ground topology:

Schottky Diode Protection for L298N Schematic showing external Schottky diodes connected in parallel to motor terminals for back-EMF protection in an L298N motor driver circuit. L298N Motor MBR0540 MBR0540 OUT1 OUT2 Vs GND Back-EMF path Back-EMF path
Diagram Description: The section on electrical noise and voltage spikes would benefit from a diagram showing the placement of external Schottky diodes relative to the motor terminals and L298N outputs.

5. Official Datasheets and Manuals

5.1 Official Datasheets and Manuals

5.2 Recommended Online Resources

5.3 Advanced Projects and Modifications