Skip to content

PicoCar Hardware Reference

Complete pin mapping and hardware configuration for the PicoCar robot platform.

Pin Mapping Diagram

                    ┌─────────────────────┐
                    │    Raspberry Pi     │
                    │      Pico W         │
                    │                     │
    Ultrasonic ───▶ │ GP0  (TRIG)        │
    Ultrasonic ◀─── │ GP1  (ECHO)        │
                    │ GP2                 │
                    │ GP3                 │
                    │ GP4                 │
                    │ GP5                 │
    NeoPixel LEDs ──│ GP6  (WS2812B)     │
    IR Receiver ────│ GP7                 │
                    │ GP8                 │
                    │ GP9                 │
    Motor R FWD ────│ GP10 (R_A)         │
    Motor R BWD ────│ GP11 (R_B)         │
    Motor L BWD ────│ GP12 (L_A)         │
    Motor L FWD ────│ GP13 (L_B)         │
    I2C SDA ────────│ GP14 (I2C1)        │
    I2C SCL ────────│ GP15 (I2C1)        │
                    │                     │
                    │ 3.3V ──── IMU VCC   │
                    │ GND  ──── IMU GND   │
                    └─────────────────────┘

I2C Configuration

Bus Selection

Pin to Bus Mapping

The Pico has two I2C buses with specific pin assignments:

Bus SDA Pins SCL Pins
I2C0 GP0, 4, 8, 12, 16, 20 GP1, 5, 9, 13, 17, 21
I2C1 GP2, 6, 10, 14, 18, 26 GP3, 7, 11, 15, 19, 27

PicoCar uses GP14 (SDA) and GP15 (SCL), which are on I2C1:

from machine import I2C, Pin

# Correct - using I2C1
i2c = I2C(1, sda=Pin(14), scl=Pin(15), freq=400000)

# Wrong - will error "bad SCL pin"
i2c = I2C(0, sda=Pin(14), scl=Pin(15), freq=400000)

I2C Devices

Device Address Chip ID Notes
BMI160 IMU 0x68 0xD1 SDO=GND
BMI160 IMU 0x69 0xD1 SDO=VCC
SSD1306 OLED 0x3C - 128x64

Motor Configuration

Pin Mapping

Motor Forward Backward Notes
Left GP13 (L_B) GP12 (L_A)
Right GP10 (R_A) GP11 (R_B)

PWM Settings

from machine import PWM, Pin

# PWM frequency
MOTOR_PWM_FREQ = 1000  # Hz

# Duty cycle scaling (0-255 → 0-65535)
PWM_SCALE = 257  # 257 * 255 = 65535

# Example: Set left motor forward at 50% speed
left_fwd = PWM(Pin(13))
left_fwd.freq(MOTOR_PWM_FREQ)
left_fwd.duty_u16(128 * PWM_SCALE)  # 50% duty

Direction Control

Left Right Motion
FWD FWD Forward
BWD BWD Backward
FWD BWD Turn right (spin)
BWD FWD Turn left (spin)
FWD (fast) FWD (slow) Curve right

Ultrasonic Sensor

Pin Mapping

Pin GPIO Direction
TRIG GP0 Output
ECHO GP1 Input

Usage

from machine import Pin
import time

trig = Pin(0, Pin.OUT)
echo = Pin(1, Pin.IN)

def measure_cm():
    # Send trigger pulse
    trig.value(0)
    time.sleep_us(2)
    trig.value(1)
    time.sleep_us(10)
    trig.value(0)

    # Wait for echo
    while echo.value() == 0:
        pass
    start = time.ticks_us()

    while echo.value() == 1:
        pass
    end = time.ticks_us()

    # Calculate distance
    duration = time.ticks_diff(end, start)
    distance_cm = duration * 0.01715  # speed of sound / 2
    return distance_cm

BMI160 IMU

Specifications

Parameter Value
I2C Address 0x68 (SDO=GND)
Chip ID 0xD1
Accel Range ±2g default
Accel Sensitivity 16384 LSB/g
Gyro Range ±250°/s default
Gyro Sensitivity 131.2 LSB/°/s
Max ODR 1600 Hz (accel), 3200 Hz (gyro)
Noise (accel) 180 µg/√Hz
Current 0.95 mA (normal mode)

vs MPU6050

Feature MPU6050 BMI160 Improvement
Accel Noise 400 µg/√Hz 180 µg/√Hz 2.2× better
Current 3.9 mA 0.95 mA 4× lower
Max ODR 1 kHz 1.6 kHz 1.6× faster
Byte Order Big-endian Little-endian Different!

Register Map (Key Registers)

Register Address Description
CHIP_ID 0x00 Should read 0xD1
DATA_GYR_X 0x0C Gyro X (2 bytes, LE)
DATA_ACC_X 0x12 Accel X (2 bytes, LE)
ACC_CONF 0x40 Accel ODR + bandwidth
ACC_RANGE 0x41 Accel range (±2/4/8/16g)
GYR_CONF 0x42 Gyro ODR + bandwidth
GYR_RANGE 0x43 Gyro range
CMD 0x7E Command register

Initialization Sequence

# 1. Soft reset
i2c.writeto_mem(0x68, 0x7E, bytes([0xB6]))
time.sleep_ms(100)

# 2. Verify chip ID
chip_id = i2c.readfrom_mem(0x68, 0x00, 1)[0]
assert chip_id == 0xD1

# 3. Enable accelerometer
i2c.writeto_mem(0x68, 0x7E, bytes([0x11]))
time.sleep_ms(10)

# 4. Enable gyroscope
i2c.writeto_mem(0x68, 0x7E, bytes([0x15]))
time.sleep_ms(100)

# 5. Configure ODR (800Hz) and range
i2c.writeto_mem(0x68, 0x40, bytes([0x2B]))  # ACC: 800Hz, normal BW
i2c.writeto_mem(0x68, 0x41, bytes([0x03]))  # ACC: ±2g
i2c.writeto_mem(0x68, 0x42, bytes([0x2B]))  # GYR: 800Hz, normal BW
i2c.writeto_mem(0x68, 0x43, bytes([0x03]))  # GYR: ±250°/s

Reading Data

import struct

# Read all 12 bytes in one transaction
data = i2c.readfrom_mem(0x68, 0x0C, 12)

# Unpack as little-endian signed 16-bit
gx, gy, gz, ax, ay, az = struct.unpack('<hhhhhh', data)

# Scale to physical units
ax_g = ax / 16384.0
gx_dps = gx / 131.2

Network Configuration

Parameter Value
WiFi Set in code
Data Port 5005 (robot → host)
Command Port 5006 (host → robot)
Debug Port 5008 (logging)

Power

Rail Voltage Notes
VBUS 5V USB power
3V3 3.3V Logic, sensors
VSYS 1.8-5.5V Battery input
IMU Voltage

The BMI160 uses 3.3V logic. Do not connect to 5V!

File Locations

File Description
src/picobot/lib/bmi160.py Full BMI160 driver
src/picobot/lib/picobot/ PicoCar hardware abstraction
src/picobot/collector.py Simple data collector
src/picobot/host/viewer.py Full visualization UI