Skip to content

Advanced 18: Closed-Loop Line Following

Prerequisites: Advanced 17 (Encoder Turns) + Tutorial: Line Following Time: ~75 min


Overview

In the Line Following tutorial, you built a P-controller for steering — but the robot's speed was open-loop. Push it too fast and the wheels slip, the robot overshoots corners, and it flies off the track. This module layers encoder speed control underneath the steering controller, creating a cascaded control system: the outer loop handles steering (line sensor → direction), the inner loop handles speed (encoder → PWM).

The result: faster reliable lap times and a robot that holds the line even at high speed.

You'll learn:

  • Why open-loop speed limits your line follower's performance
  • Cascaded control: inner speed loop + outer steering loop
  • How to combine line-sensor steering with encoder speed matching
  • Data-driven comparison: with vs without speed control
  • The concept of speed adaptation based on track curvature

Part 1: The Speed Problem (~15 min)

Why Speed Control Matters for Line Following

Your line follower from the tutorial works like this:

Line sensor → Error → P-Controller → Steering correction → Motor PWM

The steering correction adjusts the difference between left and right PWM. But the base speed is a fixed constant. Problems:

  1. Battery drains → same PWM = slower speed → robot may stall on curves
  2. Push speed higher → wheels spin faster than traction allows → slip on corners
  3. Left ≠ right motor → at high base speed, the speed mismatch adds to steering error

Task 1 — Measure the Failure Point

Run your line follower at increasing base speeds until it fails:

from picobot import Robot
import time

robot = Robot(line_sensors=True)

KP = ___  # Your tuned steering Kp from the Line Following tutorial
# Sensor weights: how much each sensor pulls the steering
# Left-most sensor pulls hard left (-2), right-most pulls hard right (+2)
W_FAR_LEFT = -2
W_LEFT     = -0.5
W_RIGHT    =  0.5
W_FAR_RIGHT = 2

def line_follow(base_speed, duration=10):
    """Run line follower for duration seconds. Returns True if stayed on line."""
    lost_count = 0

    try:
        for _ in range(int(duration / 0.02)):
            s = robot.line_sensors.read()  # [far_left, left, right, far_right]
            error = s[0]*W_FAR_LEFT + s[1]*W_LEFT + s[2]*W_RIGHT + s[3]*W_FAR_RIGHT
            correction = KP * error

            left = base_speed + correction
            right = base_speed - correction
            robot.set_motors(int(left), int(right))

            # Detect if we've lost the line
            if all(v < 100 for v in s):
                lost_count += 1
                if lost_count > 10:
                    return False
            else:
                lost_count = 0

            time.sleep(0.02)
    finally:
        robot.stop()

    return True

# Test increasing speeds
print("Finding maximum reliable open-loop speed")
print("=" * 45)

for speed in range(60, 200, 20):
    input(f"Speed {speed} — place on track, Enter...")
    ok = line_follow(speed, duration=8)
    status = "OK" if ok else "LOST LINE"
    print(f"  Base speed {speed}: {status}")
    if not ok:
        print(f"\n  Max reliable open-loop speed: ~{speed - 20}")
        break

Your max reliable open-loop speed: ______ PWM


Part 2: Cascaded Control (~25 min)

The Architecture

Add encoder speed control as an inner loop underneath the steering:

                    OUTER LOOP (steering)
Line sensor → Error → P-Controller → Target speed L, R
                    INNER LOOP (speed)      ▼
Target speed L ──►(+)──► P-Controller ──► PWM_L ──► Motor L ──┐
                  │-│                                          │
                  ▲                                            │
                  └──────────────── Encoder L ◄────────────────┘

Target speed R ──►(+)──► P-Controller ──► PWM_R ──► Motor R ──┐
                  │-│                                          │
                  ▲                                            │
                  └──────────────── Encoder R ◄────────────────┘

The outer loop decides what speed each wheel should have. The inner loop makes that speed happen regardless of battery voltage, friction, or motor differences.

Task 2 — Build the Cascaded Controller

from picobot import Robot
import time

robot = Robot(line_sensors=True, encoders=True)

# === Steering parameters (outer loop) ===
KP_STEER = ___      # From Line Following tutorial
# Sensor weights: how much each sensor pulls the steering
# Left-most sensor pulls hard left (-2), right-most pulls hard right (+2)
W_FAR_LEFT = -2
W_LEFT     = -0.5
W_RIGHT    =  0.5
W_FAR_RIGHT = 2
BASE_SPEED = 600    # ticks/sec — can go higher than open-loop!

# === Speed parameters (inner loop) ===
KP_SPEED = ___      # From Module 16 tuning
pwm_left = 0.0
pwm_right = 0.0

print(f"Cascaded line following: base={BASE_SPEED} tps")
input("Place on track. Press Enter...")

try:
    while True:
        # --- Outer loop: steering ---
        s = robot.line_sensors.read()  # [far_left, left, right, far_right]
        steer_error = s[0]*W_FAR_LEFT + s[1]*W_LEFT + s[2]*W_RIGHT + s[3]*W_FAR_RIGHT
        correction = KP_STEER * steer_error

        # Target speeds for each wheel (in ticks/sec)
        target_left = BASE_SPEED + correction
        target_right = BASE_SPEED - correction

        # --- Inner loop: speed control ---
        robot.encoders.update()

        error_l = target_left - robot.encoders.left.speed_tps
        pwm_left = max(0, min(255, pwm_left + KP_SPEED * error_l))

        error_r = target_right - robot.encoders.right.speed_tps
        pwm_right = max(0, min(255, pwm_right + KP_SPEED * error_r))

        robot.set_motors(int(pwm_left), int(pwm_right))
        time.sleep(0.02)

except KeyboardInterrupt:
    pass
finally:
    robot.stop()
    print("Stopped.")

Task 3 — Find the New Speed Limit

Repeat the speed test from Task 1, now with cascaded control:

from picobot import Robot
import time

robot = Robot(line_sensors=True, encoders=True)

KP_STEER = ___
KP_SPEED = ___
# Sensor weights: how much each sensor pulls the steering
# Left-most sensor pulls hard left (-2), right-most pulls hard right (+2)
W_FAR_LEFT = -2
W_LEFT     = -0.5
W_RIGHT    =  0.5
W_FAR_RIGHT = 2

def line_follow_cascaded(base_speed_tps, duration=10):
    """Cascaded line follower. Returns True if stayed on line."""
    pwm_l, pwm_r = 0.0, 0.0
    lost_count = 0

    try:
        for _ in range(int(duration / 0.02)):
            s = robot.line_sensors.read()
            steer_error = s[0]*W_FAR_LEFT + s[1]*W_LEFT + s[2]*W_RIGHT + s[3]*W_FAR_RIGHT
            correction = KP_STEER * steer_error

            target_l = base_speed_tps + correction
            target_r = base_speed_tps - correction

            robot.encoders.update()
            err_l = target_l - robot.encoders.left.speed_tps
            pwm_l = max(0, min(255, pwm_l + KP_SPEED * err_l))
            err_r = target_r - robot.encoders.right.speed_tps
            pwm_r = max(0, min(255, pwm_r + KP_SPEED * err_r))

            robot.set_motors(int(pwm_l), int(pwm_r))

            if all(v < 100 for v in s):
                lost_count += 1
                if lost_count > 10:
                    return False
            else:
                lost_count = 0

            time.sleep(0.02)
    finally:
        robot.stop()
    return True

print("Finding maximum reliable CASCADED speed")
print("=" * 50)

for speed in range(400, 1200, 100):
    input(f"Speed {speed} tps — place on track, Enter...")
    ok = line_follow_cascaded(speed, duration=8)
    status = "OK" if ok else "LOST LINE"
    print(f"  Base speed {speed} tps: {status}")
    if not ok:
        print(f"\n  Max reliable cascaded speed: ~{speed - 100} tps")
        break

Comparison:

Controller Max reliable speed Notes
Open-loop (PWM) ______ PWM
Cascaded (encoder) ______ tps
Note

The units are different (PWM vs tps), so direct comparison is tricky. What matters: can the cascaded version follow the track at speeds where the open-loop version fails?


Part 3: Log and Compare (~15 min)

Task 4 — Data-Logged Comparison

Log both controllers on the same track section:

from picobot import Robot
import time

robot = Robot(line_sensors=True, encoders=True)

KP_STEER = ___
KP_SPEED = ___
# Sensor weights: how much each sensor pulls the steering
# Left-most sensor pulls hard left (-2), right-most pulls hard right (+2)
W_FAR_LEFT = -2
W_LEFT     = -0.5
W_RIGHT    =  0.5
W_FAR_RIGHT = 2
BASE_SPEED_TPS = 500  # Use a speed where both work, to compare quality
DURATION = 8
DT = 0.02

# --- Cascaded run with logging ---
f = open("cascaded_log.csv", "w")
f.write("time_ms,steer_error,target_l,target_r,actual_l,actual_r,pwm_l,pwm_r\n")

pwm_l, pwm_r = 0.0, 0.0
start = time.ticks_ms()

print("Cascaded run — logging...")
try:
    for _ in range(int(DURATION / DT)):
        s = robot.line_sensors.read()  # [far_left, left, right, far_right]
        steer_error = s[0]*W_FAR_LEFT + s[1]*W_LEFT + s[2]*W_RIGHT + s[3]*W_FAR_RIGHT
        correction = KP_STEER * steer_error

        target_l = BASE_SPEED_TPS + correction
        target_r = BASE_SPEED_TPS - correction

        robot.encoders.update()
        err_l = target_l - robot.encoders.left.speed_tps
        pwm_l = max(0, min(255, pwm_l + KP_SPEED * err_l))
        err_r = target_r - robot.encoders.right.speed_tps
        pwm_r = max(0, min(255, pwm_r + KP_SPEED * err_r))

        robot.set_motors(int(pwm_l), int(pwm_r))

        elapsed = time.ticks_diff(time.ticks_ms(), start)
        f.write(f"{elapsed},{steer_error:.1f},"
                f"{target_l:.0f},{target_r:.0f},"
                f"{robot.encoders.left.speed_tps:.0f},"
                f"{robot.encoders.right.speed_tps:.0f},"
                f"{pwm_l:.0f},{pwm_r:.0f}\n")

        time.sleep(DT)
finally:
    robot.stop()
    f.close()
    print("Saved: cascaded_log.csv")

Plot the data on your computer: target vs actual speeds for both wheels, overlaid with steering error. In the cascaded version, you should see the actual speeds tracking the targets closely, even during turns.


Part 4: Speed Adaptation (Stretch) (~15 min)

Task 5 — Slow for Curves, Fast on Straights

The ultimate trick: adjust base speed based on how much the robot is turning. Large steering error = sharp curve = slow down. Small error = straight = speed up.

# Replace fixed BASE_SPEED with adaptive speed:
MAX_SPEED = 800     # tps on straights
MIN_SPEED = 300     # tps on sharp curves
CURVE_SENSITIVITY = 200  # How aggressively to slow for curves

# In the control loop:
steer_error = s[0]*W_FAR_LEFT + s[1]*W_LEFT + s[2]*W_RIGHT + s[3]*W_FAR_RIGHT
curve_factor = abs(steer_error) / CURVE_SENSITIVITY
base_speed = MAX_SPEED - (MAX_SPEED - MIN_SPEED) * min(1.0, curve_factor)

correction = KP_STEER * steer_error
target_left = base_speed + correction
target_right = base_speed - correction

Test: fastest reliable lap

Strategy Lap time Lost line?
Fixed low speed
Fixed high speed
Adaptive speed
Checkpoint — Cascaded Control Working

The cascaded controller should allow higher reliable speeds than the open-loop version. The adaptive speed variant should produce the fastest lap without losing the line. If it doesn't, revisit your inner-loop Kp from Module 16 — the speed controller needs to be fast enough to track the varying targets.


What You Discovered

Concept What You Learned
Cascaded control Inner loop (speed) + outer loop (steering) = better than either alone
Speed as a variable Steering commands target speeds, not raw PWM
Inner loop bandwidth Speed controller must be fast enough to follow steering demands
Speed adaptation Slow for curves, fast on straights — uses steering error as curvature proxy
Data-driven comparison Log both controllers, plot, compare — don't guess

The Full Track

You've now completed the encoder-based control track:

13: Encoder Fundamentals     → Understand the sensor
14: Drive Straight           → Match two wheels
15: Drive to Distance        → Odometry + velocity profiles
16: Speed Control Lab        → Log, plot, tune with data
17: Precise Turns            → Differential kinematics
18: Closed-Loop Line Follow  → Cascaded control — the payoff

Each module built on the last, and at every step you followed the same methodology: measure → calibrate → control → verify.

Further Reading


← Back to Advanced Topics