Skip to content

openpilot codebase analysis

martinl edited this page Oct 28, 2025 · 3 revisions

openpilot codebase analysis

What is openpilot?

openpilot is an open-source operating system for robotics that currently upgrades the driver assistance system in 300+ supported cars. It's developed by comma.ai and provides advanced driver assistance features including:

  • Adaptive Cruise Control (ACC) - speed and following distance control
  • Automated Lane Centering (ALC) - steering control to keep the car centered in the lane
  • Forward Collision Warning (FCW) - alerts for potential collisions
  • Lane Departure Warning (LDW) - alerts when drifting out of lane
  • Driver Monitoring (DM) - camera-based alerting for distracted/drowsy drivers

Architecture & Main Components

1. Core System (system/)

  • manager/ - Orchestrates all processes, manages lifecycle of the entire openpilot system
  • camerad/ - Camera daemon that captures video from multiple cameras (road, driver, wide-angle)
  • loggerd/ - Logging system that records all sensor data, CAN messages, and system state
  • updated/ - Over-the-air update system
  • athena/ - Cloud connectivity for data upload and remote management
  • sensord/ - Manages IMU, GPS, and other sensor inputs
  • hardware/ - Hardware abstraction layer for different devices (comma 3X, PC, etc.)

2. Self-Driving Logic (selfdrive/)

modeld/ (Vision Model)

  • Runs deep learning models using tinygrad (their custom ML framework)
  • Processes camera images at 20 Hz
  • Outputs:
    • Lane lines and road edges
    • Lead vehicle detection and tracking
    • Path prediction
    • Desired curvature and acceleration
  • Uses two models:
    • Vision model: processes camera images
    • Policy model: outputs driving actions

controls/ (Control System)

  • controlsd.py - Main control daemon that:
    • Receives model predictions
    • Implements lateral (steering) control via PID/Torque controllers
    • Implements longitudinal (gas/brake) control
    • Sends actuation commands to the car
  • Lateral controllers:
    • LatControlPID - PID-based steering
    • LatControlTorque - Torque-based steering (most common)
    • LatControlAngle - Angle-based steering
  • LongControl - Manages acceleration/braking

locationd/ (Localization)

  • Fuses GPS, IMU, and vision to determine precise vehicle position
  • Runs sensor fusion with Kalman filters
  • Provides calibrated pose (position + orientation)

monitoring/ (Driver Monitoring)

  • Analyzes driver-facing camera
  • Detects distraction and drowsiness
  • Enforces safety by disengaging if driver not paying attention

car/ (Vehicle Interfaces)

  • Contained in the opendbc submodule
  • Vehicle-specific code for 300+ car models
  • Parses CAN messages from the car
  • Sends control commands via CAN

3. Hardware Interface (panda/ submodule)

panda is the critical safety hardware component:

  • STM32H725 microcontroller running custom firmware
  • Connects to the car's CAN bus
  • Safety model enforcement:
    • Validates all control commands
    • Blocks unsafe commands
    • Enforces safety limits per car model
    • Written in C with MISRA C:2012 compliance
  • Provides USB/SPI interface to openpilot software
  • Supports CAN and CAN FD protocols

4. CAN Database (opendbc/ submodule)

opendbc provides the car interface layer:

  • DBC files - Define CAN message formats for each car
  • Car interfaces - Parse car state and build control messages
  • Safety models - Firmware-level safety for each car (runs on panda)
  • Fingerprinting - Automatically identify car model via ECU firmware versions
  • Car-specific implementations:
    • carstate.py - Parses car's CAN messages
    • carcontroller.py - Builds CAN control messages
    • interface.py - High-level car interface
    • values.py - Supported car variants

5. Communication (cereal/)

cereal is the messaging system:

  • Uses Cap'n Proto for serialized messages
  • Defines all message types in .capnp files:
    • car.capnp - Car state and control messages
    • log.capnp - Logging messages
    • Custom message types
  • PubSub messaging via msgq (message queue submodule)
  • Services run at different frequencies (defined in services.py):
    • Model: 20 Hz
    • Controls: 100 Hz
    • CAN: 100 Hz
    • GPS: 10 Hz

6. Machine Learning (tinygrad/ submodule)

tinygrad is comma.ai's custom ML framework:

  • Lightweight deep learning library
  • Optimized for embedded inference
  • Supports Qualcomm GPU acceleration
  • Runs the vision and policy models

7. Supporting Libraries

  • rednose/ - Kalman filter implementation for sensor fusion
  • msgq/ - High-performance message queue
  • teleoprtc/ - WebRTC for remote teleoperation

Detailed Submodule Analysis

msgq (msgq_repo/)

Purpose: High-performance inter-process communication (IPC) system

Key Features:

  • Lock-free single producer, multi-consumer message queue
  • Zero-copy writes when message size is known in advance
  • Ring buffer implementation in shared memory
  • Multiple backends:
    • msgq - Primary implementation (lock-free ring buffer)
    • zmq - ZeroMQ backend for compatibility
    • fake - Deterministic testing backend
  • VisionIPC - Specialized IPC for large contiguous buffers (camera frames)
    • Uses GPU-accessible shared memory (ION on Qualcomm)
    • Zero-copy video frame passing between processes

Architecture:

  • Metadata section tracks read/write pointers and validity flags
  • Data buffer stores messages with 8-byte size prefix
  • Automatic reader invalidation when lagging too far behind
  • Wrap-around handling with cycle counters

Used for: All inter-process messaging in openpilot (camera frames, CAN data, control commands, sensor data)


opendbc (opendbc_repo/)

Purpose: Python API for car control and state reading

Key Features:

  • 300+ supported car models across major manufacturers
  • DBC file repository - CAN message definitions for each car
  • Car interface library (opendbc/car/):
    • carstate.py - Parse CAN to extract car state
    • carcontroller.py - Build CAN messages to control car
    • interface.py - High-level car API
    • values.py - Enumerate supported cars
    • fingerprints.py - ECU firmware version database for car identification
  • Safety models (opendbc/safety/):
    • C code that runs on panda hardware
    • Enforces safety constraints per car model
    • Validates all control commands
    • MISRA C:2012 compliant
    • 100% line coverage in tests

Structure per car brand:

opendbc/car/<brand>/
├── carstate.py          # Parse CAN messages
├── carcontroller.py     # Build control messages
├── <brand>can.py        # DBC helpers
├── fingerprints.py      # ECU firmware versions
├── interface.py         # High-level interface
├── radar_interface.py   # Parse radar (if equipped)
└── values.py            # Supported models

Safety Architecture:

  • Safety models run in panda firmware (not on main CPU)
  • controls_allowed state machine per car
  • Blocks unsafe commands (e.g., steering when too fast, acceleration limits)
  • Cannot be bypassed - hardware enforced

Used for: All car-specific integration, control, and safety enforcement


panda (panda/)

Purpose: CAN bus interface hardware and safety firmware

Hardware:

  • STM32H725 microcontroller (ARM Cortex-M7 @ 550MHz)
  • Multiple CAN/CAN-FD buses (typically 3)
  • USB 2.0 and SPI interfaces to host
  • Different variants: panda (current gen), red panda, tres

Firmware Components:

  • board/main.c - Main firmware loop
  • board/safety/ - Safety model implementations (from opendbc)
  • board/drivers/ - Hardware drivers (CAN, USB, SPI, GPIO)
  • Bootloader - Allows firmware updates over USB

Safety Features:

  • Validates every CAN message before sending to car
  • Rate limiting on control messages
  • State machine tracking (e.g., controls_allowed)
  • Watchdog timer - disables output if host crashes
  • Hardware-level enforcement - cannot be bypassed by software

Code Rigor:

  • MISRA C:2012 compliance checking via cppcheck
  • Strict compiler flags (-Wall -Wextra -Werror)
  • Hardware-in-the-loop tests on all variants
  • Unit tests for each safety model
  • Mutation testing on MISRA coverage

Python Interface:

from panda import Panda
panda = Panda()
panda.can_recv()  # Receive CAN messages
panda.can_send(addr, data, bus)  # Send CAN messages
panda.set_safety_mode(mode)  # Set safety model

Used for: Critical path between openpilot software and vehicle CAN bus


rednose (rednose_repo/)

Purpose: Advanced Kalman filter framework for sensor fusion

Key Features:

  • Extended Kalman Filter (EKF) with symbolic Jacobian computation
  • Error State Kalman Filter (ESKF) for 3D orientation
    • Uses quaternions for state, euler angles for error
    • Avoids gimbal lock and normalization issues
  • Multi-State Constraint KF (MSCKF) for visual odometry
    • Integrates feature-based vision without depth estimation
    • Avoids positive feedback loops
  • Rauch-Tung-Striebel (RTS) smoother for offline optimization
  • Mahalanobis distance outlier rejection
  • Symbolic computation of Jacobians via SymPy
    • Eliminates manual derivation errors
    • Automatic code generation to C

Implementation:

  • Python-based filter definition using SymPy
  • Automatic C code generation for efficiency
  • Templates in templates/ for common patterns
  • Helper functions in helpers/ekf_sym.py

Use Cases in openpilot:

  • locationd - GPS + IMU + visual odometry fusion
  • Calibration - Camera extrinsics calibration
  • Live parameters - Vehicle parameter estimation (stiffness, steer ratio)

Why it's powerful:

  • Handles non-linear systems elegantly
  • Optimal estimation under Gaussian noise assumptions
  • Computationally efficient (compared to particle filters)
  • Easy to design new filters in Python

Used for: All sensor fusion and state estimation in openpilot


tinygrad (tinygrad_repo/)

Purpose: Minimalist deep learning framework

Philosophy:

  • Simplicity over complexity - readable, maintainable code
  • Lazy evaluation - operations fused into minimal kernels
  • Small codebase - between PyTorch and micrograd in complexity
  • Hardware agnostic - easy to add new accelerators

Key Features:

  • Tensor operations with automatic differentiation
  • Lazy execution - computes only when .realize() called
  • Kernel fusion - multiple ops compiled into single GPU kernel
  • Multiple backends:
    • CPU, OpenCL, Metal, CUDA, AMD, Qualcomm (QCOM), WebGPU
  • Training and inference support
  • Model zoo - Can run LLaMA, Stable Diffusion, etc.

Architecture:

from tinygrad import Tensor

# Define model
x = Tensor.eye(3, requires_grad=True)
y = Tensor([[2.0, 0, -2.0]], requires_grad=True)
z = y.matmul(x).sum()

# Backward pass
z.backward()
print(x.grad)  # Automatic differentiation

Use in openpilot:

  • Vision model - Processes camera images → lane lines, lead cars
  • Policy model - Outputs desired curvature and acceleration
  • Qualcomm GPU acceleration (via QCOM backend)
  • ~20 Hz inference on comma 3X hardware

Accelerator Support:

  • Only needs ~25 low-level ops to add new hardware
  • openpilot uses QCOM backend (Qualcomm Adreno GPU)
  • Falls back to CPU if GPU unavailable

Design Principles:

  • 2-space indentation
  • 150 char line limit
  • Every line must earn its keep - no dead code
  • Readability over cleverness

Used for: All neural network inference in openpilot (vision, policy models)


teleoprtc (teleoprtc_repo/)

Purpose: WebRTC abstractions for remote operation

Key Features:

  • WebRTC communication layer
  • Enables remote access to openpilot
  • Video/audio streaming
  • Remote control capabilities

Use Cases:

  • Remote debugging and support
  • Teleoperation (remote driving assistance)
  • Live video streaming from car cameras
  • Remote system access

Integration:

  • Works with comma connect (comma.ai's web platform)
  • Secure WebRTC connections
  • Low-latency video streaming

Used for: Remote connectivity features in openpilot


How It Works (Data Flow)

1. SENSORS → camerad, sensord, pandad
   ↓
2. Camera frames + CAN data → modeld (ML inference)
   ↓
3. Model predictions → controlsd
   ↓
4. Controls compute steering/accel → panda (safety check)
   ↓
5. Panda → CAN bus → Car actuators (steering, gas, brake)

   (Everything logged by loggerd and uploaded via athena)

Safety Architecture

Multi-layered safety:

  1. Model level - Trained on safe driving data
  2. Controls level - Sanity checks on commands
  3. Panda firmware - Hard real-time safety enforcement
    • Cannot be bypassed
    • Validates every command
    • Car-specific limits
  4. Driver monitoring - Ensures driver attention
  5. ISO 26262 compliance - Functional safety standard

Key Technologies

  • Languages: Python (high-level), C/C++ (performance-critical), Cap'n Proto (messaging)
  • Build system: SCons
  • ML framework: tinygrad (custom)
  • Hardware: Qualcomm Snapdragon (comma 3X device), STM32 (panda)
  • Communication: CAN bus, ZMQ-based messaging
  • Testing: Extensive CI/CD, hardware-in-the-loop tests, software-in-the-loop simulations

Deployment

  • Runs on the comma 3X device (custom Android-based hardware)
  • Connects to car via car harness (intercepts ADAS CAN messages)
  • Uses panda for CAN interface
  • Cloud-connected for updates and data logging

Summary

openpilot is a sophisticated robotics system that enhances existing car ADAS with better vision models and control algorithms. It uses deep learning for perception, advanced control theory for actuation, and hardware-enforced safety to provide a safer and more capable driving assistance system.

Clone this wiki locally