Advanced 16: Speed Control Lab
Prerequisites: Advanced 15 (Drive to Distance) Time: ~75 min
Overview
You've been tuning controllers by feel — watching the robot and adjusting Kp until it "looks right." Real engineers don't guess: they log data, plot it, and tune from measurements. This module adds data logging to your speed controller, exports CSV files, and uses plots to systematically tune Kp.
This is the measure → model → tune workflow used in every control system, from motor drives to chemical plants.
You'll learn:
- How to log control variables (time, target, actual, PWM, error) to CSV
- How to transfer files from Pico to your computer
- How to plot and interpret controller response curves
- How to read overshoot, rise time, and steady-state error from a plot
- How to systematically tune Kp (and optionally Ki) using data
Part 1: Instrument Your Controller (~20 min)
Task 1 — Log to CSV on the Pico
Write control data to a CSV file on the Pico's filesystem:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
TARGET_SPEED = 500 # ticks/sec
KP = 0.1
pwm_output = 0.0
DURATION = 5 # seconds
DT = 0.05 # 50 ms loop
# Open CSV file for writing
f = open("speed_log.csv", "w")
f.write("time_ms,target,actual,pwm,error\n")
print(f"Logging speed control: target={TARGET_SPEED}, Kp={KP}")
print(f"Duration: {DURATION}s → {DURATION / DT:.0f} samples")
print()
start = time.ticks_ms()
try:
for i in range(int(DURATION / DT)):
enc.update()
actual = enc.speed_tps
error = TARGET_SPEED - actual
pwm_output = max(0, min(255, pwm_output + KP * error))
robot.set_motors(int(pwm_output), 0)
# Log to file
elapsed = time.ticks_diff(time.ticks_ms(), start)
f.write(f"{elapsed},{TARGET_SPEED},{actual:.1f},{pwm_output:.1f},{error:.1f}\n")
# Print progress every second
if i % 20 == 0:
print(f" t={elapsed:5d}ms actual={actual:6.0f} "
f"pwm={pwm_output:5.1f} err={error:+6.0f}")
time.sleep(DT)
finally:
robot.stop()
f.close()
print(f"\nData saved to speed_log.csv")
Task 2 — Download the CSV
Transfer the file from the Pico to your computer:
Open it in a text editor or spreadsheet — you should see columns: time_ms, target, actual, pwm, error.
Quick Sanity Check
The first few actual values should be near zero (motor not yet spinning). They should rise toward target over the first 0.5-1 second. If actual stays at zero, check your encoder wiring.
Part 2: Open-Loop Baseline (~15 min)
Before tuning the closed-loop controller, measure what happens without feedback.
Task 3 — Log Open-Loop Response
Drive at a fixed PWM and log the actual speed — no feedback, no correction:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
FIXED_PWM = 80
DURATION = 5
DT = 0.05
f = open("openloop_log.csv", "w")
f.write("time_ms,pwm,actual\n")
print(f"Open-loop: fixed PWM {FIXED_PWM}")
start = time.ticks_ms()
try:
robot.set_motors(FIXED_PWM, 0)
for i in range(int(DURATION / DT)):
enc.update()
elapsed = time.ticks_diff(time.ticks_ms(), start)
f.write(f"{elapsed},{FIXED_PWM},{enc.speed_tps:.1f}\n")
time.sleep(DT)
finally:
robot.stop()
f.close()
print("Saved: openloop_log.csv")
Download and plot this alongside the closed-loop data. You should see:
- Open-loop: speed fluctuates, no correction when it drifts
- Closed-loop: speed converges to target, controller rejects disturbances
Part 3: Plot and Interpret (~15 min)
Task 4 — Plot with Python (matplotlib)
On your computer, create a simple plotting script:
import csv
import matplotlib.pyplot as plt
def load_csv(filename):
"""Load CSV file and return dict of columns."""
data = {}
with open(filename) as f:
reader = csv.DictReader(f)
for col in reader.fieldnames:
data[col] = []
for row in reader:
for col in reader.fieldnames:
data[col].append(float(row[col]))
return data
# --- Load data ---
cl = load_csv("speed_log.csv") # Closed-loop
ol = load_csv("openloop_log.csv") # Open-loop
# --- Plot: Speed comparison ---
fig, axes = plt.subplots(2, 1, figsize=(10, 6), sharex=True)
# Top: Speed
axes[0].plot(ol["time_ms"], ol["actual"], label="Open-loop", alpha=0.7)
axes[0].plot(cl["time_ms"], cl["actual"], label="Closed-loop", alpha=0.7)
axes[0].plot(cl["time_ms"], cl["target"], "--", color="gray", label="Target")
axes[0].set_ylabel("Speed (ticks/sec)")
axes[0].legend()
axes[0].set_title("Open-loop vs Closed-loop Speed Control")
axes[0].grid(True, alpha=0.3)
# Bottom: PWM and Error
axes[1].plot(cl["time_ms"], cl["pwm"], label="PWM output", color="orange")
ax2 = axes[1].twinx()
ax2.plot(cl["time_ms"], cl["error"], label="Error", color="red", alpha=0.5)
axes[1].set_xlabel("Time (ms)")
axes[1].set_ylabel("PWM")
ax2.set_ylabel("Error (ticks/sec)")
axes[1].legend(loc="upper left")
ax2.legend(loc="upper right")
axes[1].grid(True, alpha=0.3)
plt.tight_layout()
plt.savefig("speed_control_plot.png", dpi=150)
plt.show()
No matplotlib?
You can also open the CSV in Google Sheets, Excel, or LibreOffice Calc — select columns and insert a line chart. See the Host Plotting Guide for setup and alternatives.
Reading the Plot
Annotate your plot with these key metrics:
Speed
▲
│ overshoot
│ ╱
│ ┌────╳────────────────── target
│ / ╲ settling time
│/ ╲__________________
│
│
└──┬──┬────────────────────► Time
│ │
│ └─ rise time (10% → 90%)
└─── dead time (before motor starts moving)
| Metric | What it means | Read from plot |
|---|---|---|
| Rise time | How fast speed reaches target (10% → 90%) | Time between first movement and reaching 90% of target |
| Overshoot | How much speed exceeds target before settling | Peak above target line, as % of target |
| Settling time | When speed stays within ±5% of target | Time until oscillation dies out |
| Steady-state error | Persistent gap between actual and target | Average difference after settling |
Your measurements:
| Metric | Value |
|---|---|
| Rise time | ______ ms |
| Overshoot | ______ % |
| Settling time | ______ ms |
| Steady-state error | ______ tps |
Part 4: Systematic Tuning (~20 min)
Task 5 — Kp Sweep
Run the closed-loop logger with different Kp values. Save each to a separate CSV:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
TARGET_SPEED = 500
DT = 0.05
DURATION = 4
for kp in [0.01, 0.05, 0.1, 0.3, 0.5]:
filename = f"kp_{kp}.csv"
f = open(filename, "w")
f.write("time_ms,target,actual,pwm,error\n")
pwm_output = 0.0
enc.reset()
start = time.ticks_ms()
print(f"Kp = {kp}...", end=" ")
try:
for i in range(int(DURATION / DT)):
enc.update()
actual = enc.speed_tps
error = TARGET_SPEED - actual
pwm_output = max(0, min(255, pwm_output + kp * error))
robot.set_motors(int(pwm_output), 0)
elapsed = time.ticks_diff(time.ticks_ms(), start)
f.write(f"{elapsed},{TARGET_SPEED},{actual:.1f},{pwm_output:.1f},{error:.1f}\n")
time.sleep(DT)
finally:
robot.stop()
f.close()
print(f"saved {filename}")
time.sleep(1) # Pause between runs
print("\nDone! Download all kp_*.csv files.")
Task 6 — Compare Kp Values on One Plot
import csv
import matplotlib.pyplot as plt
kp_values = [0.01, 0.05, 0.1, 0.3, 0.5]
fig, ax = plt.subplots(figsize=(10, 5))
for kp in kp_values:
data = load_csv(f"kp_{kp}.csv")
ax.plot(data["time_ms"], data["actual"], label=f"Kp = {kp}")
ax.axhline(y=500, color="gray", linestyle="--", label="Target")
ax.set_xlabel("Time (ms)")
ax.set_ylabel("Speed (ticks/sec)")
ax.set_title("P-Controller Tuning: Kp Comparison")
ax.legend()
ax.grid(True, alpha=0.3)
plt.tight_layout()
plt.savefig("kp_comparison.png", dpi=150)
plt.show()
Fill in from your plots:
| Kp | Rise time (ms) | Overshoot (%) | Settling time (ms) | Steady-state error |
|---|---|---|---|---|
| 0.01 | ||||
| 0.05 | ||||
| 0.1 | ||||
| 0.3 | ||||
| 0.5 |
The Kp Trade-off
Higher Kp = faster response but more overshoot. There's always a trade-off. The "best" Kp depends on what you value:
- Distance driving: You want low overshoot (smooth stopping) → lower Kp
- Disturbance rejection: You want fast correction → higher Kp
- Line following at speed: You need both → this is where PID helps
Task 7 (Stretch) — Add I-Term
The P-controller often has persistent steady-state error. Add an integral term to eliminate it:
# Inside your control loop, add:
integral = 0
MAX_INTEGRAL = 100 # Anti-windup limit
# In the loop:
error = TARGET_SPEED - actual
integral += error * DT
integral = max(-MAX_INTEGRAL, min(MAX_INTEGRAL, integral)) # Clamp
pwm_output = max(0, min(255, pwm_output + KP * error + KI * integral))
Try KI = 0.5 alongside your best Kp. Log and plot: does the steady-state error disappear?
Integral Windup
Without the clamp, the integral term accumulates unbounded error during startup (when the motor hasn't reached speed yet). The clamp prevents this. Watch for it in your plots — if PWM saturates at 255 for a long time after the motor reaches speed, you have windup.
Checkpoint — Data-Driven Tuning
You should now have plots comparing multiple Kp values, with quantified rise time, overshoot, and steady-state error. This is the same workflow used for tuning industrial controllers — the only difference is the scale.
What You Discovered
| Concept | What You Learned |
|---|---|
| Data logging | Log control variables to CSV for offline analysis |
| Step response | Speed vs time plot reveals controller performance |
| Rise time / overshoot / settling | Quantitative metrics that replace "it looks okay" |
| Kp trade-off | Faster response ↔ more overshoot — always a trade-off |
| Integral term | Eliminates steady-state error but introduces windup risk |
| Measure → plot → tune | Data-driven tuning, not guesswork |
Connections
- Advanced 03: Control Theory — Mathematical foundations for what you just observed
- Advanced 07: Data-Driven Methods — System identification from your logged data
- Advanced 05: Communication & Data — More sophisticated logging and visualization
What's Next?
You have a well-tuned speed controller with data to prove it. Next: Precise Turns with Encoders — use differential encoder readings to compute heading and execute accurate turns.