openpilot Documentation
Table of Contents
What is openpilot?
openpilot is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW), and Lane Departure Warning (LDW) for a growing variety of supported car makes, models, and model years. In addition, while openpilot is engaged, a camera-based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about the vehicle integration and limitations.
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
![]() |
Running on a dedicated device in a car
To use openpilot in a car, you need four things
Supported Device: A comma 3/3X. You can purchase these devices from (https://comma.ai/shop/comma-3x)
Software: The setup procedure for the comma 3/3X allows users to enter a URL for custom software. To install the release version of openpilot, use the URL
openpilot.comma.ai
. To install openpilot master (for more advanced users), use the URLinstaller.comma.ai/commaai/master
. You can replace “commaai” with another GitHub username to install a fork.Supported Car: Ensure that you have one of the 250+ supported cars. openpilot supports a wide range of car makes including Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, Ford, and many more. If your car is not officially listed as supported but has adaptive cruise control and lane-keeping assist, it’s likely capable of running openpilot.
Car Harness: You will also need a car harness to connect your comma 3/3X to your car. We have detailed instructions for how to install the harness and device in a car.
Running on PC
All openpilot services can run as usual on a PC without requiring special hardware or a car. You can also run openpilot on recorded or simulated data to develop or experiment with openpilot.
With openpilot’s tools, you can plot logs, replay drives, and watch the full-res camera streams. See the tools README for more information.
You can also run openpilot in simulation with the CARLA simulator. This allows openpilot to drive around a virtual car on your Ubuntu machine. The whole setup should only take a few minutes but does require a decent GPU.
A PC running openpilot can also control your vehicle if it is connected to a webcam, a black panda, and a harness.
Community and Contributing
openpilot is developed by comma and by users like you. We welcome both pull requests and issues on GitHub. Bug fixes and new car ports are encouraged. Check out the contributing docs.
Documentation related to openpilot development can be found on docs.comma.ai. Information about running openpilot (e.g. FAQ, fingerprinting, troubleshooting, custom forks, community hardware) should go on the wiki.
You can add support for your car by following guides we have written for Brand and Model ports. Generally, a car with adaptive cruise control and lane keep assist is a good candidate. Join our Discord to discuss car ports: most car makes have a dedicated channel.
Want to get paid to work on openpilot? comma is hiring.
And follow us on Twitter.
User Data and comma Account
By default, openpilot uploads the driving data to our servers. You can also access your data through comma connect. We use your data to train better models and improve openpilot for everyone.
openpilot is open source software: the user is free to disable data collection if they wish to do so.
openpilot logs the road-facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. The driver-facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded.
By using openpilot, you agree to our Privacy Policy. You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma for the use of this data.
Safety and Testing
openpilot observes ISO26262 guidelines, see SAFETY.md for more details.
openpilot has software-in-the-loop tests that run on every commit.
The code enforcing the safety model lives in panda and is written in C, see code rigor for more details.
panda has software-in-the-loop safety tests.
Internally, we have a hardware-in-the-loop Jenkins test suite that builds and unit tests the various processes.
panda has additional hardware-in-the-loop tests.
We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes.
Directory Structure
.
├── cereal # The messaging spec and libs used for all logs
├── common # Library like functionality we've developed here
├── docs # Documentation
├── opendbc # Files showing how to interpret data from cars
├── panda # Code used to communicate on CAN
├── third_party # External libraries
└── system # Generic services
├── camerad # Driver to capture images from the camera sensors
├── clocksd # Broadcasts current time
├── hardware # Hardware abstraction classes
├── logcatd # systemd journal as a service
├── loggerd # Logger and uploader of car data
├── proclogd # Logs information from /proc
├── sensord # IMU interface code
└── ubloxd # u-blox GNSS module interface code
└── selfdrive # Code needed to drive the car
├── assets # Fonts, images, and sounds for UI
├── athena # Allows communication with the app
├── boardd # Daemon to talk to the board
├── car # Car specific code to read states and control actuators
├── controls # Planning and controls
├── debug # Tools to help you debug and do car ports
├── locationd # Precise localization and vehicle parameter estimation
├── manager # Daemon that starts/stops all other daemons as needed
├── modeld # Driving and monitoring model runners
├── monitoring # Daemon to determine driver attention
├── navd # Turn-by-turn navigation
├── test # Unit tests, system tests, and a car simulator
└── ui # The UI
Licensing
openpilot is released under the MIT license. Some parts of the software are released under other licenses as specified.
Any user of this software shall indemnify and hold harmless Comma.ai, Inc. and its directors, officers, employees, agents, stockholders, affiliates, subcontractors and customers from and against all allegations, claims, actions, suits, demands, damages, liabilities, obligations, losses, settlements, judgments, costs and expenses (including without limitation attorneys’ fees and costs) which arise out of, relate to or result from any use of this software by user.
THIS IS ALPHA QUALITY SOFTWARE FOR RESEARCH PURPOSES ONLY. THIS IS NOT A PRODUCT. YOU ARE RESPONSIBLE FOR COMPLYING WITH LOCAL LAWS AND REGULATIONS. NO WARRANTY EXPRESSED OR IMPLIED.
General
API Documentation
Python API
C/C++ API
- openpilot
- opendbc
CANPacker
dbc
signal_lookup
message_lookup
counters
CANParser
can_valid
bus_timeout
first_sec
last_sec
last_nonempty_sec
bus_timeout_threshold
can_invalid_cnt
bus
aligned_buf
message_states
MessageState
name
address
size
parse_sigs
vals
all_vals
last_seen_nanos
check_threshold
counter
counter_fail
ignore_checksum
ignore_counter
init_crc_lookup_tables()
honda_checksum()
toyota_checksum()
subaru_checksum()
chrysler_checksum()
volkswagen_mqb_checksum()
xor_checksum()
hkg_can_fd_checksum()
pedal_checksum()
- cereal
- messaging
AlignedBuffer
words_size
Context
Event
event_fd
EventState
fds
enabled
FakePoller
sockets
FakeSubSocket
recv_called
recv_ready
state
Message
MessageBuilder
heapArray_
msgq_header_t
num_readers
write_pointer
write_uid
read_pointers
read_valids
read_uids
msgq_msg_t
data
msgq_pollitem_t
q
revents
msgq_queue_t
mmap_p
reader_id
read_uid_local
write_uid_local
read_conflate
endpoint
MSGQContext
context
MSGQMessage
MSGQPoller
polls
num_polls
MSGQPubSocket
MSGQSubSocket
timeout
Poller
PubMaster
sockets_
PubSocket
SocketEventHandle
shm_path
SubMaster
frame
poller_
messages_
services_
SubSocket
ZMQContext
ZMQMessage
ZMQPoller
ZMQPubSocket
sock
full_endpoint
ZMQSubSocket
EventPurpose
event_state_shm_mmap()
messaging_use_zmq()
msgq_wait_for_subscriber()
msgq_reset_reader()
msgq_msg_init_size()
msgq_msg_init_data()
msgq_msg_close()
msgq_new_queue()
msgq_close_queue()
msgq_init_publisher()
msgq_init_subscriber()
msgq_msg_send()
msgq_msg_recv()
msgq_msg_ready()
msgq_poll()
msgq_all_readers_updated()
- visionipc
VisionBuf
len
mmap_len
addr
frame_id
fd
rgb
width
height
stride
uv_offset
y
uv
server_id
idx
type
buf_cl
copy_q
handle
VisionIpcClient
connected
num_buffers
buffers
msg_ctx
poller
device_id
ctx
VisionIpcServer
should_exit
listener_thread
cur_idx
ipc_connect()
ipc_bind()
ipc_sendrecv_with_fds()
VisionStreamType
visionbuf_compute_aligned_width_and_height()
get_endpoint_name()
- messaging
- selfdrive
- camerad
CameraBuf
cur_frame_data
cur_yuv_buf
cur_camera_buf
camera_bufs
camera_bufs_metadata
rgb_width
rgb_height
rgb_stride
vipc_server
debayer
yuv_type
cur_buf_idx
safe_queue
frame_buf_count
CameraInfo
frame_width
frame_height
frame_stride
frame_offset
extra_height
registers_offset
stats_offset
CameraState
multi_cam_state
ci
exp_lock
exposure_time
dc_gain_enabled
dc_gain_weight
gain_idx
analog_gain_frac
exposure_time_min
exposure_time_max
dc_gain_factor
dc_gain_min_weight
dc_gain_max_weight
dc_gain_on_grey
dc_gain_off_grey
sensor_analog_gains
analog_gain_min_idx
analog_gain_max_idx
analog_gain_rec_idx
analog_gain_cost_delta
analog_gain_cost_low
analog_gain_cost_high
cur_ev
min_ev
max_ev
best_ev_score
new_exp_g
new_exp_t
measured_grey_fraction
target_grey_fraction
target_grey_factor
sensor_fd
csiphy_fd
camera_num
session_handle
sensor_dev_handle
isp_dev_handle
csiphy_dev_handle
link_handle
buf0_handle
buf_handle
sync_objs
request_ids
request_id_last
frame_id_last
idx_offset
skipped
camera_id
buf
mm
ar0231_register_lut
FrameMetadata
timestamp_sof
timestamp_eof
integ_lines
high_conversion_gain
gain
processing_time
MemoryManager
lock
handle_lookup
size_lookup
cached_allocations
video0_fd
MultiCameraState
cam_sync_fd
isp_fd
device_iommu
cdm_iommu
road_cam
wide_road_cam
driver_cam
pm
process_thread_cb
CameraType
fill_frame_data()
get_raw_frame_image()
set_exposure_target()
start_process_thread()
cameras_init()
cameras_open()
cameras_run()
cameras_close()
camerad_thread()
open_v4l_by_name_and_index()
YUV_BUFFER_COUNT
env_disable_road
env_disable_wide_road
env_disable_driver
env_debug_frames
env_log_raw_frames
env_ctrl_exp_from_params
device_acquire()
device_config()
device_control()
do_cam_control()
alloc_w_mmu_hdl()
release()
LapConv
roi_cl
result_cl
filter_cl
prg
krnl
roi_buf
result_buf
is_blur()
- locationd
Localizer
kf
calib
device_from_calib
calib_from_device
calibrated
car_speed
last_reset_time
posenet_stds
converter
unix_timestamp_millis
reset_tracker
device_fell
gps_mode
first_valid_log_time
ttff
last_gps_msg
gnss_source
observation_timings_invalid
observation_values_invalid
standstill
orientation_reset_count
gps_std_factor
gps_variance_factor
gps_vertical_variance_factor
gps_time_offset
camodo_yawrate_distribution
LocalizerGnssSource
- ui
Alert
text1
text2
status
sound
Device
awake
interactive_timeout
ignition_on
offroad_brightness
last_brightness
brightness_filter
brightness_future
UIScene
calibration_valid
calibration_wide_valid
wide_cam
view_from_calib
view_from_wide_calib
pandaType
lane_line_probs
road_edge_stds
track_vertices
lane_line_vertices
road_edge_vertices
lead_vertices
driver_pose_vals
driver_pose_diff
driver_pose_sins
driver_pose_coss
face_kpts_draw
navigate_on_openpilot
light_sensor
started
ignition
is_metric
map_on_left
longitudinal_control
started_frame
UIState
fb_w
fb_h
sm
scene
language
car_space_transform
timer
started_prev
prime_type
AudibleAlert
UIStatus
PrimeType
uiState()
device()
ui_update_params()
get_path_length_idx()
update_model()
update_dmonitoring()
update_leads()
update_line_data()
UI_BORDER_SIZE
UI_HEADER_HEIGHT
UI_FREQ
BACKLIGHT_OFFROAD
DEFAULT_CALIBRATION
default_face_kpts_3d
alert_colors
- soundd
- replay
- qt
- proclogd
- modeld
LoadYUVState
loadys_krnl
loaduv_krnl
copy_krnl
Transform
m_y_cl
m_uv_cl
loadyuv_init()
loadyuv_destroy()
loadyuv_queue()
transform_init()
transform_destroy()
transform_queue()
ModelFrame
MODEL_WIDTH
MODEL_HEIGHT
MODEL_FRAME_SIZE
buf_size
transform
loadyuv
y_cl
u_cl
v_cl
net_input_cl
input_frames
ModelOutput
plans
lane_lines
road_edges
leads
meta
pose
wide_from_device_euler
temporal_pose
road_transform
ModelOutputBlinkerProb
left
right
ModelOutputDesireProb
none
turn_left
turn_right
lane_change_left
lane_change_right
keep_left
keep_right
null
array
@1
ModelOutputDisengageProb
gas_disengage
brake_disengage
steer_override
brake_3ms2
brake_4ms2
brake_5ms2
gas_pressed
ModelOutputEdgessXY
ModelOutputFeatures
feature
ModelOutputLaneLines
mean
std
prob
ModelOutputLeadElement
x
velocity
acceleration
ModelOutputLeadPrediction
ModelOutputLeads
prediction
ModelOutputLineProbVal
val_deprecated
val
ModelOutputLinesProb
left_far
left_near
right_near
right_far
ModelOutputLinesXY
ModelOutputMeta
desire_state_prob
engaged_prob
disengage_prob
blinker_prob
desire_pred_prob
ModelOutputPlanElement
position
rotation
rotation_rate
ModelOutputPlanPrediction
ModelOutputPlans
ModelOutputPose
velocity_mean
rotation_mean
velocity_std
rotation_std
ModelOutputRoadEdges
ModelOutputRoadTransform
position_mean
position_std
ModelOutputTemporalPose
ModelOutputWideFromDeviceEuler
ModelOutputXYZ
z
ModelOutputYZ
PublishState
disengage_buffer
prev_brake_5ms2_probs
prev_brake_3ms2_probs
softmax()
sigmoid()
to_kj_array_ptr()
send_raw_pred
fill_model_msg()
fill_pose_msg()
FEATURE_LEN
HISTORY_BUFFER_LEN
DESIRE_LEN
DESIRE_PRED_LEN
TRAFFIC_CONVENTION_LEN
NAV_FEATURE_LEN
NAV_INSTRUCTION_LEN
DRIVING_STYLE_LEN
MODEL_FREQ
DISENGAGE_LEN
BLINKER_LEN
META_STRIDE
PLAN_MHP_N
LEAD_MHP_N
LEAD_TRAJ_LEN
LEAD_MHP_SELECTION
PAD_SIZE
FCW_THRESHOLD_5MS2_HIGH
FCW_THRESHOLD_5MS2_LOW
FCW_THRESHOLD_3MS2
OUTPUT_SIZE
NET_OUTPUT_SIZE
SNPEModel
model_data
snpe
input_map
output_map
output_buffer
use_tf8
output
output_size
SNPEModelInput
snpe_buffer
ThneedModel
thneed
recorded
- common
ExitHandler
power_failure
signal
do_exit
FirstOrderFilter
x_
k_
initialized_
I2CBus
i2c_fd
m
LogState
initialized
zctx
print_level
Params
params_path
prefix
RateKeeper
interval
next_frame_time
last_monitor_time
remaining_
print_delay_threshold
frame_
unique_fd
fd_
util
cl_get_device_id()
cl_create_context()
cl_program_from_source()
cl_program_from_binary()
cl_program_from_file()
cl_get_error_string()
gpio_init()
gpio_set()
gpiochip_get_ro_value_fd()
ParamKeyType
statlog_log()
statlog_log()
cloudlog_e()
sighandler_t
update_max_atomic()
MILE_TO_KM
KM_TO_MILE
MS_TO_KPH
MS_TO_MPH
METER_TO_MILE
METER_TO_FOOT
watchdog_kick()
- sensorsd
- boardd
- camerad
- rednose
EKF
kinds
feature_kinds
f_fun
F_fun
err_fun
inv_err_fun
H_mod_fun
predict
hs
Hs
updates
Hes
sets
extra_routines
EKFSym
ekf
P
msckf
N
dim_augment
dim_augment_err
dim_main
dim_main_err
dim_x
dim_err
filter_time
maha_test_kinds
quaternion_idxs
global_vars
Q
max_rewind_age
rewind_t
rewind_states
rewind_obscache
augment_times
feature_track_kinds
Estimate
xk1
xk
Pk1
Pk
t
kind
extra_args
Observation
R
EKFS
MatrixXdr
Observation
Estimate
extra_routine_t
get_ekfs()
ekf_lookup()
ekf_register()
- opendbc