Motor Control Basics

From Bespoke Robot Society
Jump to navigation Jump to search
Motor Control Basics
Competency Electronics
Difficulty Intermediate
Time Required 3-5 hours
Prerequisites Electronics Fundamentals, basic understanding of digital signals and PWM
Materials Needed Breadboard, DC motor, motor driver module (TB6612FNG or L298N), microcontroller (Raspberry Pi Pico or Arduino), power supply (6-9V), jumper wires, multimeter
Next Steps SimpleBot assembly, build Capability:Differential Drive, Sensor Interfacing

Motor Control Basics teaches you how to control DC motors in robotics applications. You'll learn about H-bridges, PWM speed control, motor driver ICs, and differential drive systems. By the end of this tutorial, you'll understand how SimpleBot controls its motors and be able to implement motor control in your own robots.

This tutorial builds on Electronics Fundamentals - you should understand voltage, current, PWM, and digital signals before proceeding.

Why Motor Control Matters

Motors are the primary actuators in mobile robotics. Understanding motor control is essential for:

  • Speed control - Make your robot go faster or slower
  • Direction control - Forward, reverse, turning
  • Precise motion - Differential drive, straight-line driving, rotation in place
  • Energy efficiency - Maximize battery life with proper motor control
  • Protection - Prevent damage to motors and electronics

Without proper motor control knowledge, you risk burning out motors, draining batteries rapidly, or damaging your microcontroller.

Part 1: DC Motor Fundamentals

How DC Motors Work

A DC (Direct Current) motor converts electrical energy into rotational motion:

  • Apply voltage across motor terminals → motor spins
  • Higher voltage = faster speed (generally)
  • Reverse polarity → motor spins in opposite direction

Key characteristics:

  • No-load speed - Maximum RPM when nothing is attached to the shaft
  • Stall current - Current drawn when motor is blocked (highest current)
  • Operating voltage - Typical range (e.g., 3V-6V for hobby motors)
  • Rated current - Typical current during normal operation
  • Torque - Rotational force the motor can produce

Current Draw and Power

Motors draw variable current depending on load:

  • No load - Minimum current (50-100mA typical for small motors)
  • Normal operation - Moderate current (200-500mA typical)
  • Stall (blocked shaft) - Maximum current (1-3A typical)
  • Startup - Brief high current spike when starting

Example: SimpleBot TT Motor

  • No-load current: ~60mA at 6V
  • Normal operation: ~200mA at 6V
  • Stall current: ~1.5A at 6V

Why this matters:

  • You cannot power motors directly from microcontroller GPIO pins (typically limited to 10-20mA)
  • Motors need dedicated power supply (not the 3.3V regulator powering your microcontroller)
  • Motor drivers must handle stall current without overheating

Back-EMF (Electromotive Force)

When a motor spins, it acts as a generator and produces voltage in the opposite direction:

  • Back-EMF increases with motor speed
  • Can damage circuits when motor suddenly stops or reverses
  • Protection required: Diodes (flyback diodes) or motor driver ICs with built-in protection

What happens without protection:

  1. Motor spinning at full speed
  2. You cut power to motor
  3. Motor's inertia keeps it spinning briefly
  4. Motor generates voltage spike (back-EMF)
  5. Voltage spike can damage transistors, microcontrollers, or other components

Solution: Use motor driver ICs (like TB6612FNG) with built-in protection, or add flyback diodes across motor terminals.

Part 2: H-Bridge Motor Drivers

What is an H-Bridge?

An H-bridge is a circuit that allows you to control motor direction by switching the polarity of voltage across the motor:

        +V
         |
    [SW1] [SW2]
         |     |
         +--M--+  (Motor)
         |     |
    [SW3] [SW4]
         |
        GND

Legend: SW = Switch, M = Motor, +V = Battery positive

The circuit forms an "H" shape - hence the name.

H-Bridge Operation

By controlling four switches (typically transistors), you can control motor direction:

SW1 SW2 SW3 SW4 Motor Action
OFF ON ON OFF Forward (current flows left-to-right)
ON OFF OFF ON Reverse (current flows right-to-left)
OFF OFF OFF OFF Coast (motor freewheels)
OFF ON OFF ON Brake (both terminals connected to +V)
ON OFF ON OFF Brake (both terminals connected to GND)
ON ON OFF OFF SHORT CIRCUIT! Never do this!

Critical rule: Never turn on SW1 and SW3 at the same time, or SW2 and SW4 at the same time - this creates a short circuit from +V to GND!

Building an H-Bridge (Educational - Not Recommended)

You could build an H-bridge using discrete transistors (4× MOSFETs), but:

  • Requires careful gate driver design
  • No built-in protection
  • Easy to make mistakes that destroy components
  • Takes up significant board space

Better approach: Use integrated H-bridge driver ICs like the TB6612FNG, L298N, or DRV8833. These have built-in protection, current limiting, and thermal shutdown.

Part 3: PWM Speed Control

How PWM Controls Motor Speed

PWM (Pulse Width Modulation) controls motor speed by rapidly switching power on and off:

  • 100% duty cycle - Always ON → full speed
  • 50% duty cycle - ON half the time → ~half speed
  • 25% duty cycle - ON quarter of the time → ~quarter speed
  • 0% duty cycle - Always OFF → motor stopped

The motor's inertia smooths out the pulses, resulting in variable speed.

PWM Frequency Selection

Typical PWM frequencies for motor control:

  • 1 kHz - 20 kHz - Most common range
  • Too low (<100 Hz) - Motor produces audible whine, rough motion
  • Too high (>50 kHz) - Switching losses in driver increase, less efficient

SimpleBot uses 1 kHz PWM - good balance between smoothness and efficiency.

PWM and Direction Control Combined

To control both speed and direction:

  1. Set direction using H-bridge control pins (IN1, IN2)
  2. Apply PWM signal to enable/PWM pin
  3. Result: Motor spins at variable speed in chosen direction

Example: TB6612FNG control

  • Set AIN1=LOW, AIN2=HIGH → Forward direction
  • Apply PWM to PWMA pin → Variable speed forward
  • Change to AIN1=HIGH, AIN2=LOW → Reverse direction

Non-Linear Speed Response

Motor speed is not linearly proportional to PWM duty cycle:

  • Below ~20% duty cycle - Motor may not turn at all (not enough torque to overcome friction)
  • 20-80% duty cycle - Approximately linear speed response
  • 80-100% duty cycle - Speed approaches maximum, less sensitivity to changes

Practical implication: You may need to calibrate motor control in software:

  • Dead zone compensation (start at 25% instead of 0%)
  • Speed mapping function (non-linear duty cycle to achieve linear speed)
  • Different motors may need different calibration

Part 4: Motor Driver ICs

The TB6612FNG Motor Driver

The TB6612FNG is SimpleBot's motor driver. It's a dual H-bridge driver that can control two DC motors independently.

Key specifications:

  • Motor voltage: 4.5V - 13.5V
  • Logic voltage: 2.7V - 5.5V (3.3V compatible!)
  • Continuous current: 1.2A per channel
  • Peak current: 3.2A per channel
  • Low voltage drop: ~0.3V (very efficient)
  • Built-in protection: Thermal shutdown, low-voltage detection

Control pins per motor:

  • PWM - Speed control (PWM signal)
  • IN1 - Direction control bit 1
  • IN2 - Direction control bit 2
  • STBY - Standby (must be HIGH to enable driver)

TB6612FNG Truth Table

For each motor (A or B):

IN1 IN2 PWM Motor Output
LOW HIGH PWM Forward (CCW)
HIGH LOW PWM Reverse (CW)
LOW LOW any Coast (freewheeling)
HIGH HIGH any Brake (short brake)

Brake vs Coast:

  • Brake (IN1=HIGH, IN2=HIGH) - Motor terminals shorted together, motor stops quickly
  • Coast (IN1=LOW, IN2=LOW) - Motor terminals disconnected, motor coasts to a stop

Wiring the TB6612FNG

Raspberry Pi Pico → TB6612FNG:
- GP14 → AIN1  (Motor A direction bit 1)
- GP15 → AIN2  (Motor A direction bit 2)
- GP16 → PWMA  (Motor A speed - PWM capable pin)
- GP17 → BIN1  (Motor B direction bit 1)
- GP18 → BIN2  (Motor B direction bit 2)
- GP19 → PWMB  (Motor B speed - PWM capable pin)
- GP20 → STBY  (Standby - enable driver)
- GND → GND    (Logic ground)

Power Supply:
- 6V Battery (+) → VM    (Motor power)
- 3.3V → VCC             (Logic power from Pico)
- GND → GND (Power)      (Shared ground)

Motors:
- Left Motor → AO1, AO2
- Right Motor → BO1, BO2

Important: Logic ground (from Pico) and power ground (from battery) must be connected together!

Code Example: TB6612FNG Control (MicroPython)

from machine import Pin, PWM

class Motor:
    """Control a single motor on TB6612FNG"""

    def __init__(self, pwm_pin, in1_pin, in2_pin, freq=1000):
        """Initialize motor control pins

        Args:
            pwm_pin: GPIO pin number for PWM control
            in1_pin: GPIO pin number for direction bit 1
            in2_pin: GPIO pin number for direction bit 2
            freq: PWM frequency in Hz (default 1000)
        """
        self.pwm = PWM(Pin(pwm_pin))
        self.pwm.freq(freq)
        self.in1 = Pin(in1_pin, Pin.OUT)
        self.in2 = Pin(in2_pin, Pin.OUT)

    def forward(self, speed):
        """Drive motor forward at specified speed

        Args:
            speed: 0-65535 (0 = stopped, 65535 = full speed)
        """
        self.in1.value(0)
        self.in2.value(1)
        self.pwm.duty_u16(speed)

    def reverse(self, speed):
        """Drive motor reverse at specified speed

        Args:
            speed: 0-65535 (0 = stopped, 65535 = full speed)
        """
        self.in1.value(1)
        self.in2.value(0)
        self.pwm.duty_u16(speed)

    def brake(self):
        """Brake motor (short brake - stops quickly)"""
        self.in1.value(1)
        self.in2.value(1)
        self.pwm.duty_u16(0)

    def coast(self):
        """Coast motor (freewheeling - stops gradually)"""
        self.in1.value(0)
        self.in2.value(0)
        self.pwm.duty_u16(0)

# Initialize standby pin
stby = Pin(20, Pin.OUT)
stby.value(1)  # Enable motor driver

# Initialize motors
left_motor = Motor(pwm_pin=16, in1_pin=14, in2_pin=15)
right_motor = Motor(pwm_pin=19, in1_pin=17, in2_pin=18)

# Example: Drive forward at 50% speed
left_motor.forward(32768)   # 50% of 65535
right_motor.forward(32768)

# Stop after 2 seconds
import time
time.sleep(2)
left_motor.brake()
right_motor.brake()

Alternative: L298N Motor Driver

The L298N is an older, more common motor driver. It's less efficient than the TB6612FNG:

L298N characteristics:

  • Voltage drop: 2-4V (vs 0.3V for TB6612FNG)
  • Maximum voltage: 46V (good for larger motors)
  • Continuous current: 2A per channel
  • Larger size, generates more heat
  • Often includes onboard voltage regulator

When to use L298N:

  • Larger motors that need >1.2A continuous current
  • Higher voltage motors (>13.5V)
  • You already have one available

When to use TB6612FNG:

  • Battery-powered robots (efficiency matters)
  • Small to medium motors (<1A typical)
  • Space-constrained designs
  • 3.3V logic (no level shifters needed)

Part 5: Differential Drive

What is Differential Drive?

Differential drive is a robot motion system using two independently-controlled wheels:

  • Left wheel and right wheel on opposite sides of robot
  • No steering mechanism - turns are created by speed differential
  • Simple, effective, and commonly used in mobile robots

SimpleBot uses differential drive with two TT motors and wheels.

Differential Drive Motion Control

By varying the speed of left and right wheels, you can create different motions:

Left Motor Right Motor Robot Motion
Forward 50% Forward 50% Straight forward
Reverse 50% Reverse 50% Straight reverse
Forward 100% Forward 50% Gentle turn right (arc)
Forward 50% Forward 100% Gentle turn left (arc)
Forward 50% Stop Sharp turn right
Forward 50% Reverse 50% Rotate clockwise (pivot turn)
Stop Stop Stopped

Key insight: The difference in wheel speeds determines turn radius. Equal speeds = straight line.

Implementing Differential Drive

class DifferentialDrive:
    """Differential drive robot control"""

    def __init__(self, left_motor, right_motor):
        """Initialize with two Motor objects"""
        self.left = left_motor
        self.right = right_motor

    def drive(self, left_speed, right_speed):
        """Drive with independent wheel speeds

        Args:
            left_speed: -65535 to 65535 (negative = reverse)
            right_speed: -65535 to 65535 (negative = reverse)
        """
        # Left motor
        if left_speed > 0:
            self.left.forward(left_speed)
        elif left_speed < 0:
            self.left.reverse(-left_speed)
        else:
            self.left.coast()

        # Right motor
        if right_speed > 0:
            self.right.forward(right_speed)
        elif right_speed < 0:
            self.right.reverse(-right_speed)
        else:
            self.right.coast()

    def forward(self, speed):
        """Drive straight forward"""
        self.drive(speed, speed)

    def reverse(self, speed):
        """Drive straight reverse"""
        self.drive(-speed, -speed)

    def turn_left(self, speed):
        """Turn left (arc) by slowing left wheel"""
        self.drive(speed // 2, speed)

    def turn_right(self, speed):
        """Turn right (arc) by slowing right wheel"""
        self.drive(speed, speed // 2)

    def rotate_left(self, speed):
        """Rotate left in place (pivot turn)"""
        self.drive(-speed, speed)

    def rotate_right(self, speed):
        """Rotate right in place (pivot turn)"""
        self.drive(speed, -speed)

    def stop(self):
        """Stop both motors"""
        self.left.brake()
        self.right.brake()

# Initialize differential drive
robot = DifferentialDrive(left_motor, right_motor)

# Drive straight forward at 50% speed
robot.forward(32768)
time.sleep(2)

# Turn right
robot.turn_right(32768)
time.sleep(1)

# Rotate in place
robot.rotate_left(32768)
time.sleep(1)

# Stop
robot.stop()

Straight-Line Driving Challenge

Problem: Even with equal PWM duty cycles, motors rarely spin at exactly the same speed due to:

  • Manufacturing tolerances
  • Different friction in gearboxes
  • Voltage drop differences
  • Wheel diameter differences

Result: Robot drifts left or right instead of going straight.

Solutions: 1. Calibration - Measure actual wheel speeds, adjust PWM to compensate 2. Closed-loop control - Use encoders (see Capability:Optical Odometry) to measure and correct speed 3. Trim adjustment - Add offset to one motor's speed in software

Example: Simple trim adjustment

# If robot drifts right, left motor is slower - add trim
LEFT_MOTOR_TRIM = 1.05   # Left motor needs 5% more power

def forward_with_trim(speed):
    left_speed = int(speed * LEFT_MOTOR_TRIM)
    right_speed = speed
    robot.drive(left_speed, right_speed)

Turn Radius Calculation

For a differential drive robot:

R=L2×vL+vRvRvL

Where:

  • R = turn radius
  • L = distance between wheels (track width)
  • v_L = left wheel velocity
  • v_R = right wheel velocity

Special cases:

  • v_L = v_R → R = infinity (straight line)
  • v_L = -v_R → R = 0 (rotation in place)
  • v_L = 0 or v_R = 0 → R = L/2 (pivot around one wheel)

Part 6: Power Management and Protection

Separate Power Supplies

Best practice: Use separate power for motors and logic:

  • Motor power - Battery (6V, 9V, 12V depending on motors)
  • Logic power - Regulated 3.3V or 5V from voltage regulator
  • Shared ground - All grounds connected together

Why separate?

  • Motors create voltage spikes and noise
  • Motor current draw can cause voltage sag
  • Microcontroller needs stable, clean voltage

SimpleBot power system:

  • 4× AA batteries (6V) → MP1584 buck converter → 5V regulated
  • 5V → Raspberry Pi Pico onboard regulator → 3.3V for microcontroller
  • Battery 6V → TB6612FNG VM pin → Motor power
  • 3.3V → TB6612FNG VCC pin → Logic power

Decoupling Capacitors

Always add capacitors:

  • 0.1µF ceramic capacitor near every IC's power pins (VCC to GND)
  • 100-1000µF electrolytic capacitor across motor power supply

Purpose:

  • Filter high-frequency noise
  • Provide local energy storage for current spikes
  • Prevent voltage droops during motor startup

Placement matters: Place decoupling capacitors as close to IC power pins as possible.

Current Limiting

Protect your system:

  • Use motor drivers rated above your motor's stall current
  • Add fuses or resettable fuses (PTC) in power supply line
  • Monitor battery voltage to prevent over-discharge

Example:

  • SimpleBot TT motors: 1.5A stall current
  • TB6612FNG rating: 1.2A continuous, 3.2A peak
  • Result: Motors protected during brief stalls, but extended stalls will trigger thermal shutdown

Thermal Management

Motor drivers generate heat, especially at high currents:

  • Heatsinks - Attach to motor driver IC if handling >1A continuously
  • Airflow - Don't enclose motor driver in sealed box
  • Thermal shutdown - Most modern drivers shut down automatically if overheating
  • Duty cycle - If driver gets too hot, reduce motor duty cycle or add cooling

Part 7: Troubleshooting Motor Control

Motor Not Spinning

Check: 1. Power supply connected? (Measure voltage at VM pin) 2. Standby pin enabled? (STBY = HIGH) 3. PWM signal present? (Use oscilloscope or LED on PWM pin) 4. Direction pins set correctly? (Not both HIGH or both LOW for some drivers) 5. Motor connected? (Check continuity of motor wires) 6. Driver overheated? (Let cool down, check for thermal shutdown)

Motor Spins Wrong Direction

Fix:

  • Swap motor wire connections (AO1 ↔ AO2)
  • Or swap IN1/IN2 control in software

Motors Work Individually But Not Together

Likely causes:

  • Insufficient current from power supply (voltage sags when both motors run)
  • Wiring error (check all ground connections)
  • Shared PWM channel (each motor needs independent PWM)

Motors Run Erratically or Stall

Check:

  • Battery voltage sufficient? (Use multimeter under load)
  • Stall current within driver rating?
  • Decoupling capacitors installed?
  • Mechanical binding? (Wheels rubbing, gears jammed)

Robot Drives Straight But Won't Turn

Debug:

  • Test each motor independently (forward, reverse, variable speed)
  • Check that both motors are receiving different commands during turns
  • Verify IN1/IN2 pins controlling direction correctly
  • Ensure motors can reverse (not just stop)

Robot Veers to One Side

Solutions:

  • Calibrate motor speeds (add trim adjustment)
  • Check wheel diameter (uneven wheels cause drift)
  • Use encoders for closed-loop speed control
  • Verify both motors receiving same PWM value when driving straight

Part 8: Advanced Topics

Motor Speed Measurement

To achieve precise speed control, measure actual motor speed:

  • Optical encoders - Count pulses from slotted wheel (see Capability:Optical Odometry)
  • Hall effect sensors - Count magnet passes
  • Back-EMF sensing - Measure motor's generated voltage when coasting

Why measure speed?

  • Compensate for manufacturing differences
  • Implement PID control for precise motion
  • Measure distance traveled
  • Detect wheel slip or stalls

PID Control for Motors

PID (Proportional-Integral-Derivative) control maintains consistent motor speed:

  • Measure actual speed (using encoders)
  • Compare to desired speed (setpoint)
  • Calculate error and adjust PWM duty cycle
  • Result: Motor maintains target speed despite varying load

Benefits:

  • Straight-line driving without drift
  • Consistent speed regardless of battery voltage
  • Precise turns and rotations

This is an advanced topic - start with open-loop control (no feedback), then add encoders later.

Acceleration and Deceleration

Instant speed changes stress motors and can cause wheel slip. Instead, ramp speed gradually:

def ramp_speed(motor, target_speed, steps=20, delay_ms=50):
    """Gradually increase motor speed to target

    Args:
        motor: Motor object
        target_speed: Desired final speed (0-65535)
        steps: Number of incremental steps
        delay_ms: Delay between steps in milliseconds
    """
    current_speed = 0
    step_size = target_speed // steps

    for i in range(steps):
        current_speed += step_size
        motor.forward(current_speed)
        time.sleep_ms(delay_ms)

    # Final step to exact target
    motor.forward(target_speed)

Regenerative Braking

Some motor drivers support regenerative braking - converting motor's kinetic energy back into electrical energy:

  • Motor acts as generator when coasting
  • Energy charges battery or dissipates in brake resistor
  • More efficient than friction braking
  • Requires specialized motor driver with regen support

Most hobby motor drivers (including TB6612FNG) use dynamic braking (short brake) instead - motor energy dissipates as heat in the motor and driver.

Part 9: Practical Skills Checklist

By now, you should be able to:

  • ☐ Explain how DC motors work and why they draw variable current
  • ☐ Describe what back-EMF is and why protection is needed
  • ☐ Understand how H-bridges enable direction control
  • ☐ Explain how PWM controls motor speed
  • ☐ Wire a TB6612FNG motor driver to a microcontroller and motors
  • ☐ Write code to drive motors forward, reverse, and stop
  • ☐ Implement differential drive motion (forward, turn, rotate)
  • ☐ Troubleshoot common motor control problems
  • ☐ Understand the importance of separate power supplies
  • ☐ Calculate current requirements for motor selection

If you can check most of these boxes, you're ready to build robots with motor control!

Next Steps

Build SimpleBot

Apply your motor control knowledge:

Add Sensors

Combine motor control with sensing:

Expand Capabilities

Common Mistakes and Pitfalls

  • Powering motors from microcontroller pins - GPIO pins cannot supply enough current; always use motor driver
  • No standby pin control - TB6612FNG requires STBY=HIGH to enable; forgetting this means motors won't work
  • Separate grounds - Logic ground and motor ground must be connected together
  • Insufficient decoupling - Missing capacitors cause erratic behavior and voltage spikes
  • Exceeding current rating - Using motors with stall current higher than driver rating damages driver
  • No back-EMF protection - If building H-bridge from transistors, must add flyback diodes
  • PWM frequency too low - Causes audible motor whine and rough motion
  • Forgetting motor trim - Robots rarely drive perfectly straight without calibration

Resources and Further Reading

BRS Wiki Pages

External Resources

See Also