Sensor Interfacing

From Bespoke Robot Society
Jump to navigation Jump to search
Sensor Interfacing
Competency Electronics
Difficulty Intermediate
Time Required 4-6 hours
Prerequisites Electronics Fundamentals, MicroPython Basics, basic understanding of digital signals
Materials Needed Microcontroller (Raspberry Pi Pico), breadboard, I2C sensor (MPU6050 IMU), analog sensor (photoresistor), digital sensor (IR line detector), 10kΩ resistors, jumper wires, multimeter, logic analyzer (optional but helpful)
Next Steps Add IMU or distance sensors to your robot, MicroPython Programming, build advanced capabilities

Sensor Interfacing teaches you how to connect and read sensors in robotics applications. You'll learn about communication protocols (I2C, SPI), analog sensors with ADC, pull-up resistors, and active HIGH/LOW logic. By the end of this tutorial, you'll be able to integrate new sensors into your robots and troubleshoot sensor communication issues.

This tutorial builds on Electronics Fundamentals and MicroPython Basics - you should understand voltage, digital signals, and basic Python programming.

Why Sensor Interfacing Matters

Sensors are your robot's perception of the world:

  • Vision - Detect lines, obstacles, colors (cameras, distance sensors)
  • Motion - Measure acceleration, rotation, orientation (IMUs, gyroscopes)
  • Position - Track wheel rotation, distance traveled (encoders, odometry)
  • Environment - Detect light, temperature, sound (photoresistors, thermistors, microphones)

Without proper sensor interfacing, you cannot:

  • Add new capabilities to your robot
  • Debug sensor communication problems
  • Select appropriate sensors for your application
  • Understand sensor datasheets and specifications

Part 1: Sensor Types and Outputs

Digital Sensors

Digital sensors output HIGH or LOW signals:

  • Active HIGH - HIGH means "detected" (e.g., button pressed = HIGH)
  • Active LOW - LOW means "detected" (e.g., Infrared Line Detector on black line = LOW)

Example: SimpleBot line sensors

  • Output HIGH when no line (white surface reflects IR light)
  • Output LOW when on line (black tape absorbs IR light)

Reading digital sensors:

from machine import Pin

# Configure with pull-up resistor (sensor is active LOW)
sensor = Pin(10, Pin.IN, Pin.PULL_UP)

if sensor.value() == 0:  # LOW = line detected
    print("Line detected!")
else:
    print("No line")

Analog Sensors

Analog sensors output variable voltage:

  • Photoresistor - Resistance changes with light (requires voltage divider)
  • Temperature sensor - Voltage proportional to temperature
  • Potentiometer - Voltage varies from 0V to Vcc
  • Pressure sensor - Voltage indicates force

ADC (Analog-to-Digital Conversion) converts voltage to number:

  • Raspberry Pi Pico: 12-bit ADC (0-4095) with 3.3V reference
  • ESP32: 12-bit ADC (0-4095) with configurable reference
  • Arduino Uno: 10-bit ADC (0-1023) with 5V reference

Reading analog sensors:

from machine import ADC

# Configure ADC on GPIO26 (ADC0 on Raspberry Pi Pico)
sensor = ADC(26)

# Read raw ADC value (0-65535 on Pico using 16-bit conversion)
raw_value = sensor.read_u16()

# Convert to voltage (Pico uses 3.3V reference)
voltage = raw_value * 3.3 / 65535

print(f"ADC: {raw_value}, Voltage: {voltage:.2f}V")

Communication Protocol Sensors

Advanced sensors use digital communication protocols:

  • I2C - Two-wire bus, multiple devices, addresses (IMUs, distance sensors)
  • SPI - Four-wire, high-speed, chip-select per device (displays, SD cards)
  • UART - Two-wire, point-to-point (GPS modules, serial sensors)
  • 1-Wire - Single data wire (temperature sensors)

Most modern robot sensors use I2C because:

  • Only 2 wires (SDA and SCL) for multiple devices
  • Built-in addressing (up to 127 devices on one bus)
  • Widely supported by microcontrollers
  • Good for moderate-speed data (100 kHz - 400 kHz typical)

Part 2: Pull-up and Pull-down Resistors

The Floating Input Problem

Digital inputs must be either HIGH or LOW - never floating (undefined):

  • Floating input - Not connected to anything, voltage drifts randomly
  • Symptom - Erratic readings, false triggers, unpredictable behavior
  • Solution - Pull-up or pull-down resistor

Pull-up Resistors

Pull-up resistor connects input to HIGH voltage (3.3V or 5V):

    +3.3V
      |
     [10kΩ]  ← Pull-up resistor
      |
      +------- Input Pin
      |
    [Switch] ← When closed, pulls to GND
      |
     GND

Behavior:

  • Switch open → Input = HIGH (pulled up by resistor)
  • Switch closed → Input = LOW (connected to GND)

Default state: HIGH

Example: I2C communication requires pull-ups on SDA and SCL lines

Pull-down Resistors

Pull-down resistor connects input to LOW voltage (GND):

    +3.3V
      |
    [Switch] ← When closed, pulls to +3.3V
      |
      +------- Input Pin
      |
     [10kΩ]  ← Pull-down resistor
      |
     GND

Behavior:

  • Switch open → Input = LOW (pulled down by resistor)
  • Switch closed → Input = HIGH (connected to +3.3V)

Default state: LOW

Internal Pull-up/Pull-down

Most microcontrollers have internal pull-up/pull-down resistors (typically 10-50kΩ):

from machine import Pin

# Enable internal pull-up
sensor_pull_up = Pin(10, Pin.IN, Pin.PULL_UP)

# Enable internal pull-down
sensor_pull_down = Pin(11, Pin.IN, Pin.PULL_DOWN)

# No pull resistor (floating - avoid this for digital inputs!)
sensor_floating = Pin(12, Pin.IN)  # BAD PRACTICE

When to use external pull-ups:

  • I2C communication (typically 4.7kΩ or 10kΩ)
  • Multiple devices sharing the same line
  • When internal pull-up is too weak (long wires, high capacitance)

Resistor Value Selection

Typical values:

  • 10kΩ - General-purpose pull-up/pull-down
  • 4.7kΩ - I2C pull-ups (standard value)
  • 1kΩ - Strong pull-up for high-speed or long wires
  • 100kΩ - Weak pull-up to save power

Trade-offs:

  • Lower resistance (1kΩ) - Stronger pull, faster signals, more power consumption
  • Higher resistance (100kΩ) - Weaker pull, slower signals, less power consumption

Rule of thumb: 10kΩ works for most applications. Use 4.7kΩ for I2C.

Part 3: I2C Communication

What is I2C?

I2C (Inter-Integrated Circuit) is a two-wire communication protocol:

  • SDA - Serial Data (bidirectional data line)
  • SCL - Serial Clock (clock signal from master)
  • Plus - Ground (GND) and power (VCC)

Characteristics:

  • Multi-master, multi-slave (but typically one master)
  • 7-bit or 10-bit device addresses
  • Speeds: 100 kHz (standard), 400 kHz (fast), up to 3.4 MHz (high-speed)
  • Open-drain design requires pull-up resistors

I2C Device Addressing

Each I2C device has a unique 7-bit address (0x00 - 0x7F):

Common sensor addresses:

  • MPU6050 IMU - 0x68 (default) or 0x69 (alternate)
  • VL53L0X distance sensor - 0x29
  • BMP280 pressure sensor - 0x76 or 0x77
  • OLED display (SSD1306) - 0x3C or 0x3D

Address conflicts: If two sensors have the same address, you cannot use them on the same I2C bus (unless they have configurable addresses via ADR pin).

Wiring I2C Sensors

Raspberry Pi Pico → MPU6050 IMU:
- GP0 (I2C0 SDA) → SDA
- GP1 (I2C0 SCL) → SCL
- 3.3V → VCC
- GND → GND

Pull-up resistors (4.7kΩ):
- SDA to 3.3V
- SCL to 3.3V

Note: Some breakout boards have built-in pull-ups

Important:

  • Use I2C-capable pins (check your microcontroller pinout)
  • Raspberry Pi Pico has two I2C buses: I2C0 (GP0/GP1, GP4/GP5, etc.) and I2C1 (GP2/GP3, GP6/GP7, etc.)
  • Add pull-up resistors if not present on breakout board

I2C Code Example: Scanning for Devices

from machine import I2C, Pin

# Initialize I2C bus
i2c = I2C(0, scl=Pin(1), sda=Pin(0), freq=400000)

# Scan for devices
devices = i2c.scan()

if devices:
    print(f"Found {len(devices)} I2C device(s):")
    for device in devices:
        print(f"  - Address: 0x{device:02X}")
else:
    print("No I2C devices found")

Expected output (MPU6050 connected):

Found 1 I2C device(s):
  - Address: 0x68

I2C Code Example: Reading MPU6050 IMU

from machine import I2C, Pin
import time
import struct

class MPU6050:
    """Simple MPU6050 IMU driver"""

    # I2C address
    ADDR = 0x68

    # Register addresses
    PWR_MGMT_1 = 0x6B  # Power management
    ACCEL_XOUT_H = 0x3B  # Accelerometer data start
    GYRO_XOUT_H = 0x43   # Gyroscope data start

    def __init__(self, i2c):
        """Initialize MPU6050 on given I2C bus"""
        self.i2c = i2c

        # Wake up sensor (clear sleep bit)
        self.i2c.writeto_mem(self.ADDR, self.PWR_MGMT_1, b'\x00')
        time.sleep_ms(100)

    def read_accel(self):
        """Read accelerometer data (m/s²)

        Returns:
            Tuple (x, y, z) in m/s²
        """
        # Read 6 bytes starting at ACCEL_XOUT_H
        data = self.i2c.readfrom_mem(self.ADDR, self.ACCEL_XOUT_H, 6)

        # Unpack as three 16-bit signed integers (big-endian)
        ax, ay, az = struct.unpack('>hhh', data)

        # Convert to m/s² (16384 LSB/g for default ±2g range)
        scale = 9.81 / 16384
        return (ax * scale, ay * scale, az * scale)

    def read_gyro(self):
        """Read gyroscope data (deg/s)

        Returns:
            Tuple (x, y, z) in deg/s
        """
        # Read 6 bytes starting at GYRO_XOUT_H
        data = self.i2c.readfrom_mem(self.ADDR, self.GYRO_XOUT_H, 6)

        # Unpack as three 16-bit signed integers (big-endian)
        gx, gy, gz = struct.unpack('>hhh', data)

        # Convert to deg/s (131 LSB/(deg/s) for default ±250 deg/s range)
        scale = 1 / 131
        return (gx * scale, gy * scale, gz * scale)

# Initialize I2C and sensor
i2c = I2C(0, scl=Pin(1), sda=Pin(0), freq=400000)
imu = MPU6050(i2c)

# Read sensor data
while True:
    accel = imu.read_accel()
    gyro = imu.read_gyro()

    print(f"Accel: X={accel[0]:6.2f} Y={accel[1]:6.2f} Z={accel[2]:6.2f} m/s²")
    print(f"Gyro:  X={gyro[0]:6.2f} Y={gyro[1]:6.2f} Z={gyro[2]:6.2f} deg/s")
    print()

    time.sleep(0.5)

I2C Troubleshooting

No devices found (empty scan):

  • Check wiring (SDA, SCL, GND, VCC all connected)
  • Verify power supply (3.3V or 5V depending on sensor)
  • Check pull-up resistors (need 4.7kΩ on SDA and SCL)
  • Try lower I2C frequency (100 kHz instead of 400 kHz)
  • Verify I2C pins (use correct pins for your microcontroller)

OSError: [Errno 5] EIO (Input/Output Error):

  • Wrong I2C address (use scan to find actual address)
  • Sensor not responding (check power, try different sensor)
  • Bus contention (multiple masters or short circuit)

Intermittent readings:

  • Weak pull-up resistors (use 4.7kΩ or 2.2kΩ)
  • Long wires (keep I2C wires <1 meter, preferably <30cm)
  • EMI interference (route I2C wires away from motors)
  • Bad connections (check breadboard connections)

Part 4: Analog Sensors and ADC

Voltage Dividers for Resistive Sensors

Many sensors (photoresistors, thermistors, FSRs) are variable resistors. To read them, create a voltage divider:

    +3.3V
      |
     [R1]  ← Fixed resistor (e.g., 10kΩ)
      |
      +------- ADC Input (Vout)
      |
  [Photoresistor] ← Variable resistor
      |
     GND

Vout = 3.3V × R_photo / (R1 + R_photo)

How it works:

  • Bright light → Photoresistor low resistance (~1kΩ) → Vout low
  • Dark → Photoresistor high resistance (~100kΩ) → Vout high

Reading Analog Sensors

Example: Photoresistor for optical encoders (SimpleBot)

from machine import ADC, Pin
import time

# Configure ADC on GP26 (ADC0)
photoresistor = ADC(26)

# Read continuously
while True:
    # Read 16-bit value (0-65535)
    raw = photoresistor.read_u16()

    # Convert to voltage (3.3V reference)
    voltage = raw * 3.3 / 65535

    # Convert to percentage (0-100%)
    percentage = raw / 655.35

    print(f"Raw: {raw:5d}  Voltage: {voltage:.2f}V  Brightness: {percentage:.1f}%")
    time.sleep(0.1)

ADC Reference Voltage

Reference voltage is the maximum voltage the ADC can read:

  • Raspberry Pi Pico - 3.3V reference (ADC input max 3.3V)
  • ESP32 - Configurable (0-3.3V typical, can be attenuated to read higher voltages)
  • Arduino Uno - 5V reference (ADC input max 5V)

Critical warning: Exceeding ADC input voltage can damage your microcontroller!

Voltage divider for higher voltages: To measure a 9V battery with a 3.3V ADC:

    +9V Battery
      |
     [20kΩ]  ← R1
      |
      +------- ADC Input (Vout = 3V when battery = 9V)
      |
     [10kΩ]  ← R2
      |
     GND

Vout = Vin × R2 / (R1 + R2) = 9V × 10kΩ / 30kΩ = 3V
# Read battery voltage (9V nominal, divided by 3)
adc = ADC(26)
raw = adc.read_u16()
divided_voltage = raw * 3.3 / 65535
actual_voltage = divided_voltage * 3  # Multiply by divider ratio
print(f"Battery: {actual_voltage:.2f}V")

ADC Noise and Averaging

ADC readings contain noise. Averaging multiple readings improves stability:

def read_adc_average(adc, samples=10):
    """Read ADC and return average of multiple samples

    Args:
        adc: ADC object
        samples: Number of samples to average

    Returns:
        Average ADC value (0-65535)
    """
    total = 0
    for _ in range(samples):
        total += adc.read_u16()
    return total // samples

# Usage
adc = ADC(26)
averaged_value = read_adc_average(adc, samples=20)
print(f"Averaged ADC: {averaged_value}")

Optical Encoders (SimpleBot Example)

SimpleBot uses optical encoders to measure wheel rotation:

  • Slotted wheel attached to motor shaft
  • LED shines through slots
  • Photoresistor detects light pulses
  • Count pulses to measure distance
from machine import ADC
import time

# Configure optical encoder on ADC0
encoder = ADC(26)

# Threshold for detecting slot vs spoke
THRESHOLD = 30000  # Tune based on your setup

# Track state
pulse_count = 0
prev_state = False

while True:
    # Read sensor
    value = encoder.read_u16()

    # Detect light (slot) or dark (spoke)
    current_state = (value > THRESHOLD)

    # Count rising edges (transition from dark to light)
    if current_state and not prev_state:
        pulse_count += 1
        print(f"Pulse count: {pulse_count}")

    prev_state = current_state
    time.sleep(0.01)  # Poll at 100 Hz

Better approach: Use interrupts for faster, more reliable pulse counting (see advanced section).

Part 5: SPI Communication

What is SPI?

SPI (Serial Peripheral Interface) is a four-wire communication protocol:

  • MOSI - Master Out, Slave In (data from controller to device)
  • MISO - Master In, Slave Out (data from device to controller)
  • SCK - Serial Clock (clock signal from master)
  • CS - Chip Select (one per device, active LOW)

Characteristics:

  • Full-duplex (simultaneous send and receive)
  • High speed (MHz range, faster than I2C)
  • No addressing (use CS pin to select device)
  • Requires one CS pin per device

Common SPI devices:

  • SD cards
  • TFT displays
  • LoRa radio modules
  • Flash memory chips
  • ADC/DAC chips

Wiring SPI Devices

Raspberry Pi Pico → SPI Device:
- GP18 (SPI0 SCK) → SCK
- GP19 (SPI0 MOSI) → MOSI
- GP16 (SPI0 MISO) → MISO
- GP17 (any GPIO) → CS
- 3.3V → VCC
- GND → GND

Multiple devices:
- Share SCK, MOSI, MISO
- Each device gets unique CS pin

SPI Code Example: Reading an ID Register

from machine import SPI, Pin

# Initialize SPI bus
spi = SPI(0, baudrate=1000000, polarity=0, phase=0,
          sck=Pin(18), mosi=Pin(19), miso=Pin(16))

# Chip select pin
cs = Pin(17, Pin.OUT)
cs.value(1)  # Deselect (CS is active LOW)

def read_device_id(register_addr):
    """Read device ID register via SPI

    Args:
        register_addr: Register address to read

    Returns:
        Register value
    """
    cs.value(0)  # Select device

    # Write register address
    spi.write(bytearray([register_addr]))

    # Read response
    response = spi.read(1)

    cs.value(1)  # Deselect device

    return response[0]

# Example: Read ID register at 0x0F (common for many sensors)
device_id = read_device_id(0x0F)
print(f"Device ID: 0x{device_id:02X}")

SPI vs I2C Comparison

Feature I2C SPI
Wires 2 (SDA, SCL) 4 (MOSI, MISO, SCK, CS)
Speed 100-400 kHz typical 1-10 MHz typical
Addressing 7-bit address Chip Select pin
Multiple devices Easy (shared bus) Requires one CS pin per device
Complexity Moderate Simple hardware, more wiring
Power Lower Higher (faster switching)
Distance <1m typical <30cm typical

When to use I2C:

  • Multiple sensors with unique addresses
  • Moderate data rates
  • Fewer available GPIO pins

When to use SPI:

  • High-speed data (displays, SD cards)
  • Full-duplex communication needed
  • Plenty of GPIO pins available

Part 6: Debugging Sensor Communication

Logic Analyzer

A logic analyzer captures and displays digital signals:

  • Shows timing of SDA, SCL, MOSI, MISO, etc.
  • Decodes I2C, SPI, UART protocols automatically
  • Essential for debugging communication issues

Affordable options:

  • Saleae Logic clone ($10-20) - 8 channels, USB
  • DSLogic Plus ($100) - 16 channels, high speed
  • Oscilloscope with protocol decode ($200+) - Shows analog waveforms too

How to use: 1. Connect logic analyzer probes to I2C/SPI lines (SDA, SCL, etc.) 2. Connect ground to circuit ground 3. Capture communication sequence 4. Analyze timing, decode data, identify errors

I2C Debugging Checklist

If I2C communication fails:

1. Scan for devices - Does `i2c.scan()` find your sensor? 2. Check address - Is device address correct? (Some have alternate addresses) 3. Verify wiring - SDA, SCL, GND, VCC all connected? 4. Pull-up resistors - 4.7kΩ on SDA and SCL? 5. Power supply - Is sensor getting correct voltage (3.3V or 5V)? 6. Clock speed - Try lower frequency (100 kHz instead of 400 kHz) 7. Multiple masters - Only one device should control I2C bus 8. Cable length - Keep I2C wires short (<30cm preferred)

Common Sensor Problems

Sensor returns garbage data:

  • Incorrect data format (check datasheet for byte order, signed/unsigned)
  • Wrong register address
  • Sensor needs initialization sequence
  • Data needs calibration or offset correction

Sensor works then stops:

  • Power supply voltage sag (motors drawing too much current)
  • Loose connection (check breadboard contacts)
  • Thermal shutdown (sensor overheating)
  • EMI from motors (add capacitors, shield wires)

Readings are noisy or fluctuate:

  • ADC noise (use averaging, add filter capacitor)
  • EMI from motors (route sensor wires away from motor wires)
  • Poor ground connection (ensure solid GND)
  • Floating inputs (add pull-up/pull-down resistors)

Multimeter Debugging

Use a multimeter to check:

1. Power supply - Measure voltage at sensor VCC pin (should be 3.3V or 5V) 2. Ground continuity - Check continuity between sensor GND and microcontroller GND 3. Signal levels - Measure SDA/SCL when idle (should be pulled up to 3.3V/5V) 4. Analog sensor output - Measure voltage at ADC pin (should vary with sensor input)

Part 7: Advanced Sensor Techniques

Interrupts for Fast Sensors

Polling (checking sensor in loop) is slow and wastes CPU time. Interrupts trigger code immediately when signal changes:

from machine import Pin

# Global counter
pulse_count = 0

def encoder_interrupt(pin):
    """Called when encoder signal changes"""
    global pulse_count
    pulse_count += 1

# Configure encoder pin with interrupt
encoder_pin = Pin(10, Pin.IN, Pin.PULL_UP)
encoder_pin.irq(trigger=Pin.IRQ_RISING, handler=encoder_interrupt)

# Main loop can do other things
while True:
    print(f"Pulses: {pulse_count}")
    time.sleep(1)

When to use interrupts:

  • High-speed encoders (>100 Hz)
  • Critical timing (missing a pulse matters)
  • Freeing CPU for other tasks

When NOT to use interrupts:

  • Slow sensors (<10 Hz) - polling is simpler
  • Complex processing needed - interrupts should be fast
  • Debugging (harder to troubleshoot)

Kalman Filters for Sensor Fusion

Combine multiple sensors for better accuracy:

  • IMU + Encoders - Accurate position and orientation
  • Camera + Distance sensor - 3D object localization
  • GPS + IMU - Precise outdoor navigation

Kalman filter is an algorithm that optimally combines sensor data, accounting for noise and uncertainty. This is an advanced topic beyond this tutorial.

Low-Pass Filters for Noisy Sensors

Low-pass filter smooths noisy analog readings:

class LowPassFilter:
    """Simple exponential moving average low-pass filter"""

    def __init__(self, alpha=0.1):
        """Initialize filter

        Args:
            alpha: Smoothing factor (0-1). Lower = smoother but slower.
        """
        self.alpha = alpha
        self.value = None

    def update(self, new_value):
        """Update filter with new reading

        Args:
            new_value: Latest sensor reading

        Returns:
            Filtered value
        """
        if self.value is None:
            self.value = new_value
        else:
            self.value = self.alpha * new_value + (1 - self.alpha) * self.value
        return self.value

# Usage
filter = LowPassFilter(alpha=0.2)
adc = ADC(26)

while True:
    raw = adc.read_u16()
    filtered = filter.update(raw)
    print(f"Raw: {raw:5d}  Filtered: {filtered:5.0f}")
    time.sleep(0.1)

Alpha parameter:

  • alpha = 1.0 - No filtering (output = input)
  • alpha = 0.5 - Moderate filtering
  • alpha = 0.1 - Heavy filtering (smooth but slow response)

Sensor Calibration

Many sensors need calibration to convert raw values to real-world units:

Example: Calibrating a line sensor threshold

from machine import Pin
import time

# Configure sensor
sensor = Pin(10, Pin.IN, Pin.PULL_UP)

# Calibration procedure
print("Calibration: Place sensor on WHITE surface")
time.sleep(3)
white_count = 0
for _ in range(100):
    if sensor.value():
        white_count += 1
    time.sleep(0.01)
white_confidence = white_count / 100

print(f"White confidence: {white_confidence:.2f}")

print("Calibration: Place sensor on BLACK surface")
time.sleep(3)
black_count = 0
for _ in range(100):
    if not sensor.value():
        black_count += 1
    time.sleep(0.01)
black_confidence = black_count / 100

print(f"Black confidence: {black_confidence:.2f}")

# Use calibrated thresholds
if white_confidence > 0.8 and black_confidence > 0.8:
    print("Calibration successful!")
else:
    print("Calibration failed - adjust potentiometer")

Part 8: Practical Skills Checklist

By now, you should be able to:

  • ☐ Explain the difference between digital and analog sensors
  • ☐ Configure pull-up/pull-down resistors for digital inputs
  • ☐ Understand active HIGH vs active LOW logic
  • ☐ Wire and read an I2C sensor (IMU, distance sensor)
  • ☐ Scan for I2C devices and identify addresses
  • ☐ Read analog sensors using ADC
  • ☐ Create voltage dividers for resistive sensors
  • ☐ Understand SPI communication basics
  • ☐ Debug sensor communication issues with multimeter
  • ☐ Implement averaging and filtering for noisy sensors
  • ☐ Use interrupts for fast sensors (encoders)

If you can check most of these boxes, you're ready to add sensors to your robots!

Part 9: Sensor Selection Guide

Choosing the Right Sensor

Sensor Type Use Case Interface Cost Complexity
IR Line Detector Line following Digital $0.50 Beginner
Ultrasonic (HC-SR04) Obstacle avoidance Digital (trigger/echo) $1-2 Beginner
MPU6050 IMU Tilt, acceleration, rotation I2C $2-5 Intermediate
VL53L0X Distance Precise distance (2m) I2C $3-8 Intermediate
Optical Encoder Wheel rotation, odometry Analog or Digital $1-3 Intermediate
Camera (OV7670) Vision, object detection Complex (parallel/SPI) $5-15 Advanced
LIDAR (RPLidar) 360° mapping UART $100+ Advanced

Sensor Interface Summary

  • Digital (GPIO) - Simplest, on/off sensors
  • Analog (ADC) - Variable sensors, requires voltage divider for resistive sensors
  • I2C - Most common for IMU, distance, environmental sensors
  • SPI - High-speed displays, SD cards, some sensors
  • UART - GPS modules, some distance sensors
  • PWM - Servo motors, some ultrasonic sensors (output)

Next Steps

Add Sensors to Your Robot

Build Advanced Projects

  • SimpleBot - Build a robot that uses multiple sensor types
  • Activity:Maze Solving - Use distance sensors to navigate mazes
  • Create a self-balancing robot using IMU feedback

Learn More Electronics

Common Mistakes and Pitfalls

  • Missing pull-up resistors - I2C won't work without pull-ups on SDA/SCL
  • Floating inputs - Digital inputs without pull-up/pull-down give random readings
  • Wrong voltage - Exceeding ADC input voltage (3.3V on Pico) damages microcontroller
  • Incorrect I2C address - Check datasheet, some sensors have alternate addresses
  • Mixed logic levels - 5V sensor output can damage 3.3V microcontroller (use level shifter)
  • Long I2C wires - Keep I2C wires short (<30cm) to avoid communication errors
  • No common ground - Sensor GND must connect to microcontroller GND
  • Polling too slowly - Fast sensors (encoders) may miss pulses if polling is too slow

Resources and Further Reading

BRS Wiki Pages

External Resources

Datasheets

Reading datasheets is essential for sensor interfacing:

  • Sensor address and register map
  • Timing requirements
  • Power supply specifications
  • Communication protocol details

See Also