MicroPython Programming
| MicroPython Programming | |
|---|---|
| Competency | Software |
| Difficulty | Intermediate |
| Time Required | 5-8 hours (split across multiple sessions) |
| Prerequisites | MicroPython Basics, Electronics Fundamentals |
| Materials Needed | Raspberry Pi Pico, breadboard, motors with H-bridge (TB6612FNG), encoders, I2C sensor (optional: MPU6050 IMU) |
| Next Steps | State Machine Design, Behavior:PID Control, SimpleBot advanced implementations |
MicroPython Programming builds on MicroPython Basics to teach advanced techniques for robot control. This tutorial covers interrupts, PWM motor control, I2C communication, timers, and state machines - everything you need to build sophisticated robot behaviors.
By the end of this tutorial, you'll understand:
- Hardware interrupts for encoder counting
- PWM generation for precise motor speed control
- I2C communication for reading sensors (IMU example)
- Timers for non-blocking periodic tasks
- State machines for organizing complex behaviors
- Asynchronous programming with asyncio
This tutorial is hands-on and assumes you've completed MicroPython Basics.
Part 1: Hardware Interrupts
Interrupts let the microcontroller respond immediately to events without constantly checking (polling).
Why Use Interrupts?
Polling (inefficient):
while True:
if encoder.value() == 1: # Constantly checking
count += 1
# Do other work
Problem: If encoder pulse is brief, you might miss it while doing other work.
Interrupts (efficient):
def encoder_callback(pin):
count += 1 # Runs immediately when encoder pulses
encoder.irq(trigger=Pin.IRQ_RISING, handler=encoder_callback)
# Do other work - encoder is counted automatically!
Interrupt triggers a function when the event occurs, regardless of what the main loop is doing.
Basic Interrupt Example: Count Button Presses
from machine import Pin
import time
press_count = 0
def button_callback(pin):
global press_count
press_count += 1
button = Pin(14, Pin.IN, Pin.PULL_UP)
button.irq(trigger=Pin.IRQ_FALLING, handler=button_callback)
while True:
print(f"Button pressed {press_count} times")
time.sleep(1)
Explanation:
- Pin.IRQ_FALLING - Trigger when signal goes HIGH→LOW (button pressed)
- global press_count - Modify variable from interrupt handler
- Main loop can do other work while button presses are counted
Interrupt-Driven Encoder Counting
Optical encoders produce pulses as wheels rotate. Interrupts ensure no pulses are missed.
Single encoder (counts pulses):
from machine import Pin
import time
encoder_count = 0
def encoder_callback(pin):
global encoder_count
encoder_count += 1
encoder = Pin(15, Pin.IN, Pin.PULL_UP)
encoder.irq(trigger=Pin.IRQ_RISING, handler=encoder_callback)
while True:
print(f"Encoder count: {encoder_count}")
time.sleep(0.5)
Quadrature encoder (detects direction):
Quadrature encoders have two channels (A and B) that pulse 90° out of phase:
- A leads B → forward rotation
- B leads A → backward rotation
from machine import Pin
import time
encoder_count = 0
encoder_a = Pin(15, Pin.IN, Pin.PULL_UP)
encoder_b = Pin(16, Pin.IN, Pin.PULL_UP)
def encoder_a_callback(pin):
global encoder_count
if encoder_b.value() == 1:
encoder_count += 1 # Forward
else:
encoder_count -= 1 # Backward
encoder_a.irq(trigger=Pin.IRQ_RISING, handler=encoder_a_callback)
while True:
print(f"Position: {encoder_count}")
time.sleep(0.5)
Why quadrature encoding matters:
- SimpleBot's Capability:Optical Odometry uses encoder direction to track position
- Essential for Activity:Dead Reckoning and precise movement
Interrupt Best Practices
DO:
- Keep interrupt handlers SHORT and FAST
- Use global variables to pass data to main loop
- Use volatile flags to signal events
DON'T:
- Use time.sleep() in interrupt handlers (blocks everything!)
- Print in interrupt handlers (slow, can cause problems)
- Do complex calculations in interrupt handlers
Good pattern - minimal interrupt, main loop does work:
encoder_flag = False
def encoder_callback(pin):
global encoder_flag
encoder_flag = True # Just set a flag
encoder.irq(trigger=Pin.IRQ_RISING, handler=encoder_callback)
while True:
if encoder_flag:
# Do complex processing here
calculate_position()
encoder_flag = False
# Other work
time.sleep(0.01)
Part 2: PWM (Pulse Width Modulation)
PWM controls motor speed by rapidly switching power on and off.
PWM Basics
- Frequency - How fast it switches (typically 1-20 kHz for motors)
- Duty cycle - Percentage of time it's ON (0% = stopped, 100% = full speed)
Example:
- 50% duty cycle = motor at half speed
- 75% duty cycle = motor at 75% speed
PWM on Raspberry Pi Pico
from machine import Pin, PWM
# Create PWM object
motor_pwm = PWM(Pin(16))
# Set frequency (1 kHz)
motor_pwm.freq(1000)
# Set duty cycle (50% = 32768 out of 65535)
motor_pwm.duty_u16(32768)
# Other duty cycles:
motor_pwm.duty_u16(0) # 0% - stopped
motor_pwm.duty_u16(16384) # 25% - quarter speed
motor_pwm.duty_u16(49152) # 75% - three-quarter speed
motor_pwm.duty_u16(65535) # 100% - full speed
Why duty_u16?
- u16 = unsigned 16-bit integer (0-65535)
- Provides fine control (65536 different speed levels)
- Alternative: duty_ns(nanoseconds) for precise timing
Motor Control with H-Bridge
DC motors need an H-bridge to control direction and speed. Common chip: TB6612FNG.
H-bridge control signals:
- IN1, IN2 - Direction control for motor A (HIGH/LOW, LOW/HIGH)
- PWM - Speed control (duty cycle)
Motor control class:
from machine import Pin, PWM
class Motor:
def __init__(self, in1_pin, in2_pin, pwm_pin):
self.in1 = Pin(in1_pin, Pin.OUT)
self.in2 = Pin(in2_pin, Pin.OUT)
self.pwm = PWM(Pin(pwm_pin))
self.pwm.freq(1000) # 1 kHz
def forward(self, speed):
"""Drive forward at speed (0-100)"""
self.in1.high()
self.in2.low()
duty = int(speed * 65535 / 100)
self.pwm.duty_u16(duty)
def backward(self, speed):
"""Drive backward at speed (0-100)"""
self.in1.low()
self.in2.high()
duty = int(speed * 65535 / 100)
self.pwm.duty_u16(duty)
def stop(self):
"""Stop motor (brake)"""
self.in1.low()
self.in2.low()
self.pwm.duty_u16(0)
# Example usage
motor_left = Motor(in1_pin=10, in2_pin=11, pwm_pin=12)
motor_right = Motor(in1_pin=13, in2_pin=14, pwm_pin=15)
motor_left.forward(75) # Left motor 75% forward
motor_right.forward(75) # Right motor 75% forward
time.sleep(2)
motor_left.stop()
motor_right.stop()
Differential Drive Robot
Differential drive uses two independently controlled wheels:
class DifferentialDrive:
def __init__(self, motor_left, motor_right):
self.left = motor_left
self.right = motor_right
def forward(self, speed=50):
self.left.forward(speed)
self.right.forward(speed)
def backward(self, speed=50):
self.left.backward(speed)
self.right.backward(speed)
def turn_left(self, speed=50):
self.left.backward(speed)
self.right.forward(speed)
def turn_right(self, speed=50):
self.left.forward(speed)
self.right.backward(speed)
def stop(self):
self.left.stop()
self.right.stop()
# Create robot
robot = DifferentialDrive(motor_left, motor_right)
# Drive in a square
robot.forward(50)
time.sleep(1)
robot.turn_left(50)
time.sleep(0.5)
robot.stop()
This is the foundation of Capability:Differential Drive!
Part 3: I2C Communication
I2C (Inter-Integrated Circuit) is a two-wire protocol for communicating with sensors.
I2C Basics
- SDA - Serial Data (bidirectional data line)
- SCL - Serial Clock (clock signal from controller)
- Addresses - Each device has a unique 7-bit address (e.g., 0x68)
- Multi-device - Multiple sensors on same two wires
I2C on Raspberry Pi Pico
Pico has two I2C buses (I2C0, I2C1):
from machine import I2C, Pin
# I2C0 on pins 0 (SDA) and 1 (SCL)
i2c = I2C(0, scl=Pin(1), sda=Pin(0), freq=400000)
# Scan for devices
devices = i2c.scan()
print(f"I2C devices found: {[hex(d) for d in devices]}")
# Example output: ['0x68'] (MPU6050 IMU)
Reading an IMU (MPU6050)
The MPU6050 is a popular 6-axis IMU (3-axis accelerometer + 3-axis gyroscope) used for Capability:IMU Sensing.
Basic register reading:
from machine import I2C, Pin
import struct
import time
MPU6050_ADDR = 0x68
PWR_MGMT_1 = 0x6B
ACCEL_XOUT_H = 0x3B
# Initialize I2C
i2c = I2C(0, scl=Pin(1), sda=Pin(0), freq=400000)
# Wake up MPU6050 (it starts in sleep mode)
i2c.writeto_mem(MPU6050_ADDR, PWR_MGMT_1, bytes([0]))
def read_accel():
"""Read accelerometer data (X, Y, Z)"""
data = i2c.readfrom_mem(MPU6050_ADDR, ACCEL_XOUT_H, 6)
ax, ay, az = struct.unpack('>3h', data) # Big-endian signed 16-bit
# Convert to g (gravity units)
# MPU6050 default range: ±2g, scale: 16384 LSB/g
ax_g = ax / 16384.0
ay_g = ay / 16384.0
az_g = az / 16384.0
return ax_g, ay_g, az_g
while True:
ax, ay, az = read_accel()
print(f"Accel X: {ax:.2f}g, Y: {ay:.2f}g, Z: {az:.2f}g")
time.sleep(0.1)
Complete MPU6050 class:
class MPU6050:
def __init__(self, i2c, addr=0x68):
self.i2c = i2c
self.addr = addr
# Wake up MPU6050
self.i2c.writeto_mem(self.addr, 0x6B, bytes([0]))
def read_accel(self):
data = self.i2c.readfrom_mem(self.addr, 0x3B, 6)
ax, ay, az = struct.unpack('>3h', data)
return ax / 16384.0, ay / 16384.0, az / 16384.0
def read_gyro(self):
data = self.i2c.readfrom_mem(self.addr, 0x43, 6)
gx, gy, gz = struct.unpack('>3h', data)
# Gyro scale: 131 LSB/°/s
return gx / 131.0, gy / 131.0, gz / 131.0
def read_temp(self):
data = self.i2c.readfrom_mem(self.addr, 0x41, 2)
temp_raw = struct.unpack('>h', data)[0]
return temp_raw / 340.0 + 36.53 # Convert to °C
# Usage
i2c = I2C(0, scl=Pin(1), sda=Pin(0), freq=400000)
imu = MPU6050(i2c)
while True:
ax, ay, az = imu.read_accel()
gx, gy, gz = imu.read_gyro()
temp = imu.read_temp()
print(f"Accel: {ax:.2f}, {ay:.2f}, {az:.2f} | Gyro: {gx:.1f}, {gy:.1f}, {gz:.1f} | Temp: {temp:.1f}°C")
time.sleep(0.1)
Why I2C matters for robotics:
- Many sensors use I2C: IMU, magnetometer, time-of-flight, OLED display
- Two wires connect many devices (versus 1 wire per device with digital I/O)
- Libraries abstract complexity (you don't need to know every register)
Part 4: Timers and Non-Blocking Code
The Problem with time.sleep()
Blocking code:
while True:
motor.forward(50)
time.sleep(2) # Blocks for 2 seconds - can't do anything else!
motor.stop()
time.sleep(1)
Problem: Can't read sensors or respond to events during sleep.
Solution 1: Time-Based Switching
import time
state = "forward"
state_start_time = time.ticks_ms()
while True:
current_time = time.ticks_ms()
elapsed = time.ticks_diff(current_time, state_start_time)
if state == "forward":
motor.forward(50)
if elapsed > 2000: # 2 seconds
state = "stopped"
state_start_time = current_time
elif state == "stopped":
motor.stop()
if elapsed > 1000: # 1 second
state = "forward"
state_start_time = current_time
# Can read sensors and do other work here!
sensor_value = sensor.value()
print(f"Sensor: {sensor_value}")
time.sleep(0.01) # Small delay to avoid maxing CPU
Key functions:
- time.ticks_ms() - Milliseconds since boot (wraps around after ~12 days)
- time.ticks_diff(new, old) - Time difference handling wraparound
Solution 2: Hardware Timers
Hardware timers trigger a callback periodically without blocking:
from machine import Timer
led_state = False
def timer_callback(timer):
global led_state
led_state = not led_state
led.value(led_state)
# Create timer that fires every 500ms
timer = Timer(period=500, mode=Timer.PERIODIC, callback=timer_callback)
# Main loop is free to do other work!
while True:
sensor_value = sensor.value()
print(f"Sensor: {sensor_value}")
time.sleep(0.1)
When to use timers:
- Periodic sensor readings (sample IMU every 10ms)
- Blinking status LEDs without blocking
- PID control loops (run every 20ms)
Part 5: State Machines
State machines organize complex behaviors into discrete states with transitions.
Line Following State Machine
States:
- FORWARD - Both sensors on line
- TURN_LEFT - Right sensor lost line
- TURN_RIGHT - Left sensor lost line
- SEARCH - Both sensors lost line
Code:
from machine import Pin
import time
# Sensors
sensor_left = Pin(14, Pin.IN, Pin.PULL_UP)
sensor_right = Pin(15, Pin.IN, Pin.PULL_UP)
# State machine
state = "FORWARD"
while True:
left = sensor_left.value()
right = sensor_right.value()
# State transitions
if left == 0 and right == 0:
state = "FORWARD"
elif left == 0 and right == 1:
state = "TURN_LEFT"
elif left == 1 and right == 0:
state = "TURN_RIGHT"
else:
state = "SEARCH"
# State actions
if state == "FORWARD":
robot.forward(50)
print("State: FORWARD")
elif state == "TURN_LEFT":
robot.turn_left(40)
print("State: TURN_LEFT")
elif state == "TURN_RIGHT":
robot.turn_right(40)
print("State: TURN_RIGHT")
elif state == "SEARCH":
robot.turn_left(30)
print("State: SEARCH")
time.sleep(0.01)
Advanced State Machine with Timing
Add state entry/exit actions and timing:
class StateMachine:
def __init__(self):
self.state = None
self.state_start_time = 0
def change_state(self, new_state):
if new_state != self.state:
self.exit_state(self.state)
self.state = new_state
self.state_start_time = time.ticks_ms()
self.enter_state(new_state)
def enter_state(self, state):
print(f"Enter state: {state}")
# State entry actions
def exit_state(self, state):
print(f"Exit state: {state}")
# State cleanup actions
def time_in_state(self):
return time.ticks_diff(time.ticks_ms(), self.state_start_time)
# Usage
sm = StateMachine()
sm.change_state("FORWARD")
while True:
# Determine next state based on sensors
if obstacle_detected:
sm.change_state("AVOID")
elif line_detected:
sm.change_state("FOLLOW")
# Execute state behavior
if sm.state == "FORWARD":
robot.forward(50)
elif sm.state == "AVOID":
robot.turn_left(50)
if sm.time_in_state() > 1000: # Turn for 1 second
sm.change_state("FORWARD")
See State Machine Design for more advanced patterns.
Part 6: Asynchronous Programming with asyncio
asyncio allows concurrent tasks without threads (lightweight, cooperative multitasking).
Basic asyncio Example
import asyncio
from machine import Pin
led1 = Pin(16, Pin.OUT)
led2 = Pin(17, Pin.OUT)
async def blink_led1():
while True:
led1.toggle()
await asyncio.sleep(0.5) # Non-blocking sleep
async def blink_led2():
while True:
led2.toggle()
await asyncio.sleep(0.3) # Different rate
async def main():
# Run both tasks concurrently
await asyncio.gather(
blink_led1(),
blink_led2()
)
# Start event loop
asyncio.run(main())
Both LEDs blink at different rates simultaneously!
Robot with Concurrent Sensor Reading and Motor Control
import asyncio
from machine import Pin, I2C
sensor_data = {"distance": 0, "imu": (0, 0, 0)}
async def read_distance_sensor():
while True:
# Read I2C distance sensor
distance = read_distance() # Hypothetical function
sensor_data["distance"] = distance
await asyncio.sleep(0.1) # 10 Hz
async def read_imu():
while True:
# Read I2C IMU
ax, ay, az = imu.read_accel()
sensor_data["imu"] = (ax, ay, az)
await asyncio.sleep(0.01) # 100 Hz
async def motor_control():
while True:
# Use sensor data to control motors
if sensor_data["distance"] < 20:
robot.stop()
else:
robot.forward(50)
await asyncio.sleep(0.02) # 50 Hz control loop
async def main():
await asyncio.gather(
read_distance_sensor(),
read_imu(),
motor_control()
)
asyncio.run(main())
Why asyncio is useful:
- Multiple sensors at different rates (IMU at 100 Hz, distance at 10 Hz)
- Motor control loop independent of sensor reading
- No blocking delays - everything runs "simultaneously"
Part 7: Practical Example - Encoder-Based Odometry
Combine interrupts, PWM, and state machines for Activity:Dead Reckoning:
from machine import Pin, PWM
import time
import math
class Odometry:
def __init__(self, encoder_left_pin, encoder_right_pin, wheel_diameter, wheel_base, counts_per_rev):
self.wheel_diameter = wheel_diameter # mm
self.wheel_base = wheel_base # mm
self.counts_per_rev = counts_per_rev
# Position
self.x = 0.0
self.y = 0.0
self.theta = 0.0 # Heading in radians
# Encoder counts
self.left_count = 0
self.right_count = 0
# Setup encoders with interrupts
self.encoder_left = Pin(encoder_left_pin, Pin.IN, Pin.PULL_UP)
self.encoder_right = Pin(encoder_right_pin, Pin.IN, Pin.PULL_UP)
self.encoder_left.irq(trigger=Pin.IRQ_RISING, handler=self.left_callback)
self.encoder_right.irq(trigger=Pin.IRQ_RISING, handler=self.right_callback)
def left_callback(self, pin):
self.left_count += 1
def right_callback(self, pin):
self.right_count += 1
def update(self):
# Calculate distance traveled by each wheel
mm_per_count = (math.pi * self.wheel_diameter) / self.counts_per_rev
left_distance = self.left_count * mm_per_count
right_distance = self.right_count * mm_per_count
# Reset counts
self.left_count = 0
self.right_count = 0
# Calculate robot movement
distance = (left_distance + right_distance) / 2.0
delta_theta = (right_distance - left_distance) / self.wheel_base
# Update position
self.theta += delta_theta
self.x += distance * math.cos(self.theta)
self.y += distance * math.sin(self.theta)
def get_position(self):
return self.x, self.y, self.theta
# Usage
odom = Odometry(
encoder_left_pin=15,
encoder_right_pin=16,
wheel_diameter=65, # mm
wheel_base=120, # mm
counts_per_rev=20 # Pulses per revolution
)
while True:
odom.update()
x, y, theta = odom.get_position()
print(f"Position: ({x:.1f}, {y:.1f}) mm, Heading: {math.degrees(theta):.1f}°")
time.sleep(0.1)
This implements SimpleBot:Dead Reckoning Implementation!
Part 8: Skills Checklist
By now, you should be able to:
- ☐ Use hardware interrupts for encoder counting
- ☐ Generate PWM signals for motor speed control
- ☐ Control motor direction with H-bridge (TB6612FNG)
- ☐ Implement differential drive robot class
- ☐ Communicate with I2C sensors (read IMU)
- ☐ Use timers for non-blocking periodic tasks
- ☐ Write non-blocking code with time.ticks_ms()
- ☐ Design state machines for robot behaviors
- ☐ Use asyncio for concurrent tasks
- ☐ Implement encoder-based odometry
If you can check most of these boxes, you can build advanced robot behaviors!
Next Steps
Apply to Real Robots
- SimpleBot:Dead Reckoning Implementation - Encoder odometry
- SimpleBot:Line Following Implementation - State machine line follower
- Add IMU to SimpleBot for heading stabilization
Learn Advanced Techniques
- State Machine Design - Hierarchical state machines, event-driven design
- Behavior:PID Control - Closed-loop control for speed and position
- ROS Basics - Distributed robotics framework
Build New Capabilities
- Capability:Encoder Sensing - Precise wheel rotation measurement
- Capability:IMU Sensing - Orientation and acceleration
- Capability:Time-of-Flight Sensing - I2C distance measurement
Common Intermediate Mistakes
- Modifying variables in interrupts without "global" - Forgot global declaration
- Long interrupt handlers - Causes missed interrupts and timing issues
- Ignoring PWM frequency effects - Too low = audible whine, too high = inefficient
- Not debouncing switches - Mechanical switches bounce, causing multiple counts
- Forgetting I2C pull-up resistors - I2C needs 4.7kΩ pull-ups on SDA and SCL
- Race conditions in asyncio - Shared variables need careful handling
- Integer overflow in encoder counts - Use 32-bit integers or reset periodically
Debugging Advanced Programs
Logic Analyzer for I2C/SPI
Use a logic analyzer ($10-60) to visualize I2C communication:
- See SDA and SCL signals
- Decode I2C addresses and data
- Identify timing issues and protocol errors
Oscilloscope for PWM
Visualize PWM signals:
- Verify frequency and duty cycle
- Check for glitches or noise
- Measure rise/fall times
Print Timing Analysis
Measure execution time:
start = time.ticks_us()
# Code to measure
expensive_function()
elapsed = time.ticks_diff(time.ticks_us(), start)
print(f"Execution time: {elapsed} µs")
Tools and Resources
Hardware
- Logic analyzer - $10-60 (Saleae-compatible clones work well)
- Oscilloscope - $100-400 (DSO150 or Rigol DS1054Z)
- I2C sensors - MPU6050 IMU ($3), VL53L0X distance ($5)
- Motor driver - TB6612FNG breakout board ($5-10)
Software
- MicroPython I2C library - Built-in, no installation needed
- Pulseview (Free) - Logic analyzer software
- mpremote (Free) - Command-line tool for MicroPython
External Resources
See Also
- Software - Full software competency overview
- MicroPython Basics - Prerequisites for this tutorial
- State Machine Design - Advanced behavior organization
- SimpleBot - Apply these techniques to a real robot
- Behavior:PID Control - Closed-loop motor control