Advanced 9: Encoders & Speed Control
Prerequisites: Lab 4 (Motor Control) Time: ~90 min
Overview
In the Motor Control lab, you discovered that time-based motor commands produce inconsistent results — the square never closes. This module adds quadrature hall encoders to measure actual wheel rotation, then uses that feedback to build closed-loop speed control.
You'll learn:
- How quadrature encoders work (A/B channels, direction detection)
- How to read encoder ticks using hardware interrupts
- How to calibrate: ticks per revolution and ticks to distance
- How to measure real-time wheel speed
- How to build a P-controller for constant wheel speed
Part 1: Understanding Quadrature Encoders (~15 min)
What's Inside the Motor
Your new motors include hall-effect sensors — small chips that detect magnetic fields. A magnet ring attached to the motor shaft passes by two sensors (Channel A and Channel B) placed at slightly different positions.
As the motor turns, each sensor outputs a digital pulse train. The two channels are offset by 90 degrees (a quarter cycle) — this is why it's called "quadrature."
Why Two Channels?
A single channel can count rotations, but it can't tell which direction the motor is spinning. With two channels offset by 90 degrees, the relationship between them reveals direction:
Forward rotation:
Ch A: ──┐ ┌──┐ ┌──┐ ┌──
│ │ │ │ │ │
└──┘ └──┘ └──┘
Ch B: ──┐ ┌──┐ ┌──┐ ┌──
│ │ │ │ │ │
└──┘ └──┘ └──┘
↑ A rises while B is LOW → forward
Reverse rotation:
Ch A: ──┐ ┌──┐ ┌──┐ ┌──
│ │ │ │ │ │
└──┘ └──┘ └──┘
Ch B: ┐ ┌──┐ ┌──┐ ┌──┐
│ │ │ │ │ │ │
└──┘ └──┘ └──┘ └──
↑ A rises while B is HIGH → reverse
The rule: On a rising edge of Channel A, read Channel B.
- B is LOW → forward
- B is HIGH → reverse
This is exactly what the Encoder ISR does.
Why Interrupts?
At moderate motor speed, encoder pulses arrive thousands of times per second. If you use a polling loop (while True: read pin), you'll miss pulses whenever your code is doing anything else.
Hardware interrupts (IRQ) solve this: the processor automatically pauses your main code, runs a tiny handler function, and resumes — no pulses missed.
ISR Safety Rules
Code inside an interrupt handler must be minimal and allocation-free:
- No
print(), no string formatting - No list/dict creation
- No floating-point math
- Just read pins and update an integer counter
Heavy work (speed calculations, display updates) happens in your main loop.
Part 2: Reading Raw Ticks (~20 min)
Setup
The picobot library includes encoder support. Initialize the robot with encoders=True:
from picobot import Robot
import time
robot = Robot(encoders=True)
# Access the left encoder directly
enc = robot.encoders.left
Pin Configuration
The encoder pins are defined in picobot/config.py:
- Left encoder: GP20 (Ch A), GP21 (Ch B)
- Right encoder: GP18 (Ch A), GP19 (Ch B)
If your wiring is different, update config.PINS.ENCODER_LEFT_A etc.
Task 1 — Count Ticks
Drive the motor at low speed and watch the tick count update in real time:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
enc.reset()
print("Driving left motor — watch the ticks. Ctrl+C to stop.")
print()
try:
robot.set_motors(50, 0) # Left motor only, low speed
while True:
print(f"Ticks: {enc.ticks} ", end="\r")
time.sleep(0.1)
except KeyboardInterrupt:
pass
finally:
robot.stop()
print(f"\nFinal count: {enc.ticks}")
Note
The gear ratio on these motors is too high to spin the wheel by hand — you must use the motor to generate encoder pulses.
Wrong Direction?
If forward motion produces negative ticks, swap the A and B pin numbers in config.py. This is a wiring convention, not a bug.
Task 2 — Direction Detection
Drive the motor forward and backward under power, and observe the sign change:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
enc.reset()
print("Forward...")
robot.set_motors(60, 0) # Left motor only
time.sleep(1)
robot.stop()
print(f" Ticks after forward: {enc.ticks}")
time.sleep(0.5)
enc.reset()
print("Backward...")
robot.set_motors(-60, 0)
time.sleep(1)
robot.stop()
print(f" Ticks after backward: {enc.ticks}")
Expected: Forward gives a positive count, backward gives a negative count (or vice versa — see the tip above).
Checkpoint — Ticks Working
You should see tick counts changing when the wheel spins, with opposite signs for opposite directions. Typical values are hundreds to low thousands of ticks per second of rotation. If you see zero, check your wiring and pin configuration.
Part 3: Calibration (~20 min)
Why Calibrate?
Raw tick counts are meaningless until you know:
- How many ticks = one full wheel revolution (PPR — Pulses Per Revolution)
- How far the wheel travels per revolution (wheel circumference)
These two numbers convert ticks into real-world distance.
Task 3 — Ticks per Revolution
Mark the wheel with a small piece of tape or a dot. Drive the motor very slowly and count exactly one full revolution visually:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
enc.reset()
input("Mark the wheel and align to a reference point. Press Enter...")
print("Driving very slowly — press Ctrl+C after EXACTLY one revolution.")
try:
robot.set_motors(30, 0) # Very slow
while True:
print(f"Ticks: {enc.ticks} ", end="\r")
time.sleep(0.05)
except KeyboardInterrupt:
pass
finally:
robot.stop()
ppr = enc.ticks
print(f"\nTicks per revolution (PPR): {ppr}")
Tip
Use the lowest PWM that still moves the wheel. Watch the tape mark carefully and hit Ctrl+C the moment it completes one full turn.
Run this 3 times and record:
| Trial | Ticks | Notes |
|---|---|---|
| 1 | ||
| 2 | ||
| 3 |
Your PPR: ______ (should be consistent across trials)
Precision Matters
Try to align the mark as precisely as possible. The PPR value is a fixed property of your motor + encoder combination — it shouldn't change between trials. If your values vary a lot, you're probably not aligning the mark carefully enough.
Task 4 — Ticks to Distance
Measure the wheel circumference using a ruler or tape measure:
- Mark the floor at the contact point
- Roll the wheel exactly one revolution
- Measure the distance traveled: ______ mm
Or calculate it: \(C = \pi \times d\) where \(d\) is the wheel diameter in mm.
Your wheel circumference: ______ mm
Now you can convert:
Store Your Calibration
Update config.py with your measured values:
class HARDWARE:
# ... existing constants ...
# Encoders (measured by you!)
ENCODER_PPR = ___ # Your PPR value
WHEEL_CIRCUMFERENCE_MM = ___ # Your wheel circumference
Checkpoint — Calibration Complete
You should now have two numbers: PPR (ticks per revolution) and wheel circumference (mm). These are properties of YOUR hardware and won't change unless you swap motors or wheels.
Part 4: Speed Measurement (~15 min)
How Speed Is Computed
The Encoder class computes speed when you call update():
This is done in your main loop, not in the ISR. The ISR only counts ticks.
Task 5 — Real-Time Speed Display
Drive the motor at a fixed PWM and display the actual speed:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
PWM_VALUE = 80
try:
robot.set_motors(PWM_VALUE, 0) # Left motor only
print(f"PWM = {PWM_VALUE}")
print()
for _ in range(50): # 5 seconds at 100ms intervals
enc.update()
print(f"Speed: {enc.speed_tps:7.1f} ticks/sec "
f"Ticks: {enc.ticks}", end="\r")
time.sleep(0.1)
finally:
robot.stop()
print()
print(f"Final ticks: {enc.ticks}")
Record the steady-state speed: ______ ticks/sec at PWM = 80
Task 6 — Speed vs PWM Curve
The relationship between PWM command and actual speed is not linear. Let's measure it:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
print("PWM → Speed mapping")
print("=" * 35)
try:
for pwm in range(0, 260, 20):
robot.set_motors(pwm, 0)
time.sleep(0.5) # Let speed stabilize
# Average a few readings
speeds = []
for _ in range(10):
enc.update()
speeds.append(enc.speed_tps)
time.sleep(0.05)
avg_speed = sum(speeds) / len(speeds)
bar = "#" * int(avg_speed / 50)
print(f"PWM {pwm:3d}: {avg_speed:7.1f} tps {bar}")
finally:
robot.stop()
Record your results:
| PWM | Speed (ticks/sec) |
|---|---|
| 0 | |
| 20 | |
| 40 | |
| 60 | |
| 80 | |
| 100 | |
| 120 | |
| 160 | |
| 200 | |
| 255 |
Observations:
- At what PWM does the motor first start moving? ______ (this is the dead zone)
- Is the curve linear? Probably not — especially at low and high PWM values
- What happens near PWM 255? The motor can't go faster — it saturates
Checkpoint — Speed Measured
You should have a clear non-linear PWM-to-speed curve with a dead zone at low PWM and saturation at high PWM. This curve explains why open-loop control is unreliable: the same PWM produces different speeds depending on where you are on this curve.
Part 5: Closed-Loop Speed Control (~20 min)
The Idea
Instead of commanding a PWM value and hoping, you:
- Set a target speed (in ticks/sec)
- Measure actual speed (from the encoder)
- Adjust PWM to reduce the difference
This is the same feedback control concept from the line-following lab, applied to speed.
Target speed ──►(+)──► P-Controller ──► PWM ──► Motor ──► Wheel ──┐
│-│ │
▲ │
└────────────────── Encoder ◄─────────────────────┘
Task 7 (Challenge) — P-Controller for Speed
Implement a proportional speed controller:
from picobot import Robot
import time
robot = Robot(encoders=True)
enc = robot.encoders.left
# --- Control parameters ---
TARGET_SPEED = 500 # ticks/sec — adjust for your motor
KP = 0.1 # Proportional gain — start small, increase
pwm_output = 0
print(f"Target: {TARGET_SPEED} tps, Kp = {KP}")
print()
try:
for i in range(200): # Run for ~10 seconds
enc.update()
actual_speed = enc.speed_tps
# P-controller
error = TARGET_SPEED - actual_speed
pwm_output = pwm_output + KP * error
# Clamp to valid PWM range
pwm_output = max(0, min(255, pwm_output))
robot.set_motors(int(pwm_output), 0)
if i % 10 == 0: # Print every 0.5 sec
print(f"Target: {TARGET_SPEED:5.0f} "
f"Actual: {actual_speed:7.1f} "
f"Error: {error:7.1f} "
f"PWM: {pwm_output:5.1f}")
time.sleep(0.05)
finally:
robot.stop()
Tune your controller:
| Kp | Behavior |
|---|---|
| 0.01 | |
| 0.05 | |
| 0.1 | |
| 0.5 | |
| 1.0 |
What happens with too little gain? Too much?
Tuning Tips
- Too low Kp: Speed slowly creeps toward target, never quite reaches it
- Good Kp: Speed reaches target within 1-2 seconds, stays stable
- Too high Kp: Speed oscillates around target (overshoots then undershoots)
For a deeper dive into tuning, see Advanced 03: Control Theory.
The Payoff: Closed-Loop vs Open-Loop
Now the real test — does closed-loop speed control actually help the robot drive straight?
from picobot import Robot
import time
robot = Robot(encoders=True)
TARGET_SPEED = 500 # Same speed for both wheels
KP = 0.1 # Your tuned value
pwm_left = 0
pwm_right = 0
print("Closed-loop straight line test")
input("Place robot on a straight line. Press Enter...")
try:
for _ in range(100): # 5 seconds
robot.encoders.update()
# Left wheel controller
error_l = TARGET_SPEED - robot.encoders.left.speed_tps
pwm_left = max(0, min(255, pwm_left + KP * error_l))
# Right wheel controller (if encoder available)
if robot.encoders.right:
error_r = TARGET_SPEED - robot.encoders.right.speed_tps
pwm_right = max(0, min(255, pwm_right + KP * error_r))
else:
pwm_right = pwm_left # Mirror left if no right encoder
robot.set_motors(int(pwm_left), int(pwm_right))
time.sleep(0.05)
finally:
robot.stop()
print("Compare this to the open-loop straight line from Motor Control!")
Compare:
| Test | Drift over 1m |
|---|---|
| Open-loop (PWM 80, 80) | ______ cm |
| Closed-loop (encoder feedback) | ______ cm |
Checkpoint — Closed-Loop Working
The closed-loop version should drive noticeably straighter than the open-loop version. It won't be perfect (there's still no heading feedback), but matched wheel speeds dramatically reduce drift.
What You Discovered
| Concept | What You Learned |
|---|---|
| Quadrature encoding | Two channels, 90 degrees apart, detect rotation AND direction |
| ISR design | Minimal interrupt handler — count ticks only, compute speed in main loop |
| Calibration | PPR and wheel circumference convert ticks to real-world distance |
| Non-linear PWM | Same PWM command gives different speeds depending on conditions |
| Closed-loop speed | Measuring actual speed and adjusting PWM keeps wheels matched |
What's Next?
- Odometry: Integrate encoder ticks over time to estimate position — see Advanced 04: Sensor Fusion
- Full PID: Add integral and derivative terms for faster, smoother response — see Advanced 03: Control Theory
- Path planning: With known distance per tick, you can command "drive exactly 50 cm" instead of "drive for 1 second"
Key Code Reference
from picobot import Robot
# Initialize with encoder support
robot = Robot(encoders=True)
# Access encoders
robot.encoders.left.ticks # Raw signed tick count
robot.encoders.left.speed_tps # Ticks per second (call update() first)
robot.encoders.left.reset() # Zero the counter
robot.encoders.update() # Recompute speed for both encoders
# Direct encoder use (without Robot)
from picobot import Encoder
enc = Encoder(pin_a=20, pin_b=21)
enc.ticks
enc.update()
enc.speed_tps