Merge remote-tracking branch 'origin/master' into online-lag

pull/34531/head
Kacper Rączy 4 months ago
commit b7a0afc3e6
  1. 2
      common/params_keys.h
  2. 4
      conftest.py
  3. 2
      launch_env.sh
  4. 2
      msgq_repo
  5. 2
      opendbc_repo
  6. 2
      panda
  7. 3
      pyproject.toml
  8. 18
      selfdrive/controls/controlsd.py
  9. 38
      selfdrive/controls/lib/drive_helpers.py
  10. 7
      selfdrive/controls/lib/latcontrol.py
  11. 4
      selfdrive/controls/lib/latcontrol_angle.py
  12. 4
      selfdrive/controls/lib/latcontrol_pid.py
  13. 6
      selfdrive/controls/lib/latcontrol_torque.py
  14. 10
      selfdrive/controls/lib/tests/test_latcontrol.py
  15. 6
      selfdrive/selfdrived/selfdrived.py
  16. 1
      selfdrive/test/process_replay/migration.py
  17. 9
      selfdrive/test/process_replay/model_replay.py
  18. 2
      selfdrive/test/process_replay/process_replay.py
  19. 2
      selfdrive/test/process_replay/ref_commit
  20. 52
      selfdrive/test/process_replay/regen.py
  21. 2
      selfdrive/test/process_replay/regen_all.py
  22. 10
      selfdrive/test/process_replay/test_processes.py
  23. 104
      selfdrive/test/test_onroad.py
  24. 99
      selfdrive/ui/qt/offroad/firehose.cc
  25. 19
      selfdrive/ui/qt/offroad/firehose.h
  26. 22
      selfdrive/ui/translations/main_ar.ts
  27. 22
      selfdrive/ui/translations/main_de.ts
  28. 22
      selfdrive/ui/translations/main_es.ts
  29. 22
      selfdrive/ui/translations/main_fr.ts
  30. 30
      selfdrive/ui/translations/main_ja.ts
  31. 30
      selfdrive/ui/translations/main_ko.ts
  32. 30
      selfdrive/ui/translations/main_pt-BR.ts
  33. 22
      selfdrive/ui/translations/main_th.ts
  34. 22
      selfdrive/ui/translations/main_tr.ts
  35. 30
      selfdrive/ui/translations/main_zh-CHS.ts
  36. 30
      selfdrive/ui/translations/main_zh-CHT.ts
  37. 4
      system/athena/athenad.py
  38. 12
      system/hardware/tici/agnos.json
  39. 36
      system/hardware/tici/all-partitions.json
  40. 2
      tinygrad_repo
  41. 6
      tools/cabana/dbc/generate_dbc_json.py
  42. 39
      tools/car_porting/README.md
  43. 232
      tools/car_porting/examples/find_segments_with_message.ipynb
  44. 8
      tools/plotjuggler/juggle.py
  45. 4
      tools/tuning/measure_steering_accuracy.py
  46. 44
      uv.lock

@ -8,6 +8,7 @@ inline static std::unordered_map<std::string, uint32_t> keys = {
{"AdbEnabled", PERSISTENT},
{"AlwaysOnDM", PERSISTENT},
{"ApiCache_Device", PERSISTENT},
{"ApiCache_FirehoseStats", PERSISTENT},
{"AssistNowToken", PERSISTENT},
{"AthenadPid", PERSISTENT},
{"AthenadUploadQueue", PERSISTENT},
@ -36,7 +37,6 @@ inline static std::unordered_map<std::string, uint32_t> keys = {
{"ExperimentalLongitudinalEnabled", PERSISTENT | DEVELOPMENT_ONLY},
{"ExperimentalMode", PERSISTENT},
{"ExperimentalModeConfirmed", PERSISTENT},
{"FirehoseMode", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"FirmwareQueryDone", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"ForcePowerDown", PERSISTENT},
{"GitBranch", PERSISTENT},

@ -77,8 +77,10 @@ def openpilot_class_fixture():
@pytest.fixture(scope="function")
def tici_setup_fixture(openpilot_function_fixture):
def tici_setup_fixture(request, openpilot_function_fixture):
"""Ensure a consistent state for tests on-device. Needs the openpilot function fixture to run first."""
if 'skip_tici_setup' in request.keywords:
return
HARDWARE.initialize_hardware()
HARDWARE.set_power_save(False)
os.system("pkill -9 -f athena")

@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1
export VECLIB_MAXIMUM_THREADS=1
if [ -z "$AGNOS_VERSION" ]; then
export AGNOS_VERSION="11.9"
export AGNOS_VERSION="11.10"
fi
export STAGING_ROOT="/data/safe_staging"

@ -1 +1 @@
Subproject commit 095f1e23613d47031a9b23e3f9ed5dd3fe01a06e
Subproject commit ad9020c430362d17c0edf97747d344389234be4d

@ -1 +1 @@
Subproject commit bc839875bd0ca476be71dea2cbebc92a4544c40c
Subproject commit e7d08ac4794c859e604d260da010d4685c164e5b

@ -1 +1 @@
Subproject commit 2c802449fd51d9904ca265d06b7a5f9969057ae3
Subproject commit 3bf1f8e871f3c577fccba07f57958f30508a2187

@ -143,6 +143,7 @@ asyncio_default_fixture_loop_scope = "function"
markers = [
"slow: tests that take awhile to run and can be skipped with -m 'not slow'",
"tici: tests that are only meant to run on the C3/C3X",
"skip_tici_setup: mark test to skip tici setup fixture"
]
testpaths = [
"common",
@ -215,7 +216,7 @@ lint.select = [
"E", "F", "W", "PIE", "C4", "ISC", "A", "B",
"NPY", # numpy
"UP", # pyupgrade
"TRY302", "TRY400", "TRY401", # try/excepts
"TRY203", "TRY400", "TRY401", # try/excepts
"RUF008", "RUF100",
"TID251",
"PLR1704",

@ -40,7 +40,7 @@ class Controls:
'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState')
self.pm = messaging.PubMaster(['carControl', 'controlsState'])
self.steer_limited = False
self.steer_limited_by_controls = False
self.desired_curvature = 0.0
self.pose_calibrator = PoseCalibrator()
@ -109,11 +109,11 @@ class Controls:
actuators.accel = float(self.LoC.update(CC.longActive, CS, long_plan.aTarget, long_plan.shouldStop, pid_accel_limits))
# Steering PID loop and lateral MPC
self.desired_curvature = clip_curvature(CS.vEgo, self.desired_curvature, model_v2.action.desiredCurvature)
actuators.curvature = float(self.desired_curvature)
self.desired_curvature, curvature_limited = clip_curvature(CS.vEgo, self.desired_curvature, model_v2.action.desiredCurvature, lp.roll)
actuators.curvature = self.desired_curvature
steer, steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp,
self.steer_limited, self.desired_curvature,
self.calibrated_pose) # TODO what if not available
self.steer_limited_by_controls, self.desired_curvature,
self.calibrated_pose, curvature_limited) # TODO what if not available
actuators.torque = float(steer)
actuators.steeringAngleDeg = float(steeringAngleDeg)
# Ensure no NaNs/Infs
@ -161,10 +161,10 @@ class Controls:
if self.sm['selfdriveState'].active:
CO = self.sm['carOutput']
if self.CP.steerControlType == car.CarParams.SteerControlType.angle:
self.steer_limited = abs(CC.actuators.steeringAngleDeg - CO.actuatorsOutput.steeringAngleDeg) > \
STEER_ANGLE_SATURATION_THRESHOLD
self.steer_limited_by_controls = abs(CC.actuators.steeringAngleDeg - CO.actuatorsOutput.steeringAngleDeg) > \
STEER_ANGLE_SATURATION_THRESHOLD
else:
self.steer_limited = abs(CC.actuators.torque - CO.actuatorsOutput.torque) > 1e-2
self.steer_limited_by_controls = abs(CC.actuators.torque - CO.actuatorsOutput.torque) > 1e-2
# TODO: both controlsState and carControl valids should be set by
# sm.all_checks(), but this creates a circular dependency
@ -180,7 +180,7 @@ class Controls:
cs.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan']
cs.lateralPlanMonoTime = self.sm.logMonoTime['modelV2']
cs.desiredCurvature = float(self.desired_curvature)
cs.desiredCurvature = self.desired_curvature
cs.longControlState = self.LoC.long_control_state
cs.upAccelCmd = float(self.LoC.pid.p)
cs.uiAccelCmd = float(self.LoC.pid.i)

@ -1,5 +1,6 @@
import numpy as np
from cereal import log
from opendbc.car.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
from openpilot.common.realtime import DT_CTRL
MIN_SPEED = 1.0
@ -7,20 +8,33 @@ CONTROL_N = 17
CAR_ROTATION_RADIUS = 0.0
# This is a turn radius smaller than most cars can achieve
MAX_CURVATURE = 0.2
MAX_VEL_ERR = 5.0 # m/s
# EU guidelines
MAX_LATERAL_JERK = 5.0
MAX_VEL_ERR = 5.0
def clip_curvature(v_ego, prev_curvature, new_curvature):
new_curvature = np.clip(new_curvature, -MAX_CURVATURE, MAX_CURVATURE)
v_ego = max(MIN_SPEED, v_ego)
max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755
safe_desired_curvature = np.clip(new_curvature,
prev_curvature - max_curvature_rate * DT_CTRL,
prev_curvature + max_curvature_rate * DT_CTRL)
return safe_desired_curvature
MAX_LATERAL_JERK = 5.0 # m/s^3
MAX_LATERAL_ACCEL_NO_ROLL = 3.0 # m/s^2
def clamp(val, min_val, max_val):
clamped_val = float(np.clip(val, min_val, max_val))
return clamped_val, clamped_val != val
def clip_curvature(v_ego, prev_curvature, new_curvature, roll):
# This function respects ISO lateral jerk and acceleration limits + a max curvature
v_ego = max(v_ego, MIN_SPEED)
max_curvature_rate = MAX_LATERAL_JERK / (v_ego ** 2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755
new_curvature = np.clip(new_curvature,
prev_curvature - max_curvature_rate * DT_CTRL,
prev_curvature + max_curvature_rate * DT_CTRL)
roll_compensation = roll * ACCELERATION_DUE_TO_GRAVITY
max_lat_accel = MAX_LATERAL_ACCEL_NO_ROLL + roll_compensation
min_lat_accel = -MAX_LATERAL_ACCEL_NO_ROLL + roll_compensation
new_curvature, limited_accel = clamp(new_curvature, min_lat_accel / v_ego ** 2, max_lat_accel / v_ego ** 2)
new_curvature, limited_max_curv = clamp(new_curvature, -MAX_CURVATURE, MAX_CURVATURE)
return float(new_curvature), limited_accel or limited_max_curv
def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float:

@ -17,14 +17,15 @@ class LatControl(ABC):
self.steer_max = 1.0
@abstractmethod
def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose):
def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, calibrated_pose, curvature_limited):
pass
def reset(self):
self.sat_count = 0.
def _check_saturation(self, saturated, CS, steer_limited):
if saturated and CS.vEgo > self.sat_check_min_speed and not steer_limited and not CS.steeringPressed:
def _check_saturation(self, saturated, CS, steer_limited_by_controls, curvature_limited):
# Saturated only if control output is not being limited by car torque/angle rate limits
if (saturated or curvature_limited) and CS.vEgo > self.sat_check_min_speed and not steer_limited_by_controls and not CS.steeringPressed:
self.sat_count += self.sat_count_rate
else:
self.sat_count -= self.sat_count_rate

@ -11,7 +11,7 @@ class LatControlAngle(LatControl):
super().__init__(CP, CI)
self.sat_check_min_speed = 5.
def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose):
def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, calibrated_pose, curvature_limited):
angle_log = log.ControlsState.LateralAngleState.new_message()
if not active:
@ -23,7 +23,7 @@ class LatControlAngle(LatControl):
angle_steers_des += params.angleOffsetDeg
angle_control_saturated = abs(angle_steers_des - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD
angle_log.saturated = bool(self._check_saturation(angle_control_saturated, CS, False))
angle_log.saturated = bool(self._check_saturation(angle_control_saturated, CS, False, curvature_limited))
angle_log.steeringAngleDeg = float(CS.steeringAngleDeg)
angle_log.steeringAngleDesiredDeg = angle_steers_des
return 0, float(angle_steers_des), angle_log

@ -17,7 +17,7 @@ class LatControlPID(LatControl):
super().reset()
self.pid.reset()
def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose):
def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, calibrated_pose, curvature_limited):
pid_log = log.ControlsState.LateralPIDState.new_message()
pid_log.steeringAngleDeg = float(CS.steeringAngleDeg)
pid_log.steeringRateDeg = float(CS.steeringRateDeg)
@ -43,6 +43,6 @@ class LatControlPID(LatControl):
pid_log.i = float(self.pid.i)
pid_log.f = float(self.pid.f)
pid_log.output = float(output_steer)
pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_steer) < 1e-3, CS, steer_limited))
pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_steer) < 1e-3, CS, steer_limited_by_controls, curvature_limited))
return output_steer, angle_steers_des, pid_log

@ -37,7 +37,7 @@ class LatControlTorque(LatControl):
self.torque_params.latAccelOffset = latAccelOffset
self.torque_params.friction = friction
def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose):
def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, calibrated_pose, curvature_limited):
pid_log = log.ControlsState.LateralTorqueState.new_message()
if not active:
output_torque = 0.0
@ -73,7 +73,7 @@ class LatControlTorque(LatControl):
desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, friction_compensation=True,
gravity_adjusted=True)
freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5
freeze_integrator = steer_limited_by_controls or CS.steeringPressed or CS.vEgo < 5
output_torque = self.pid.update(pid_log.error,
feedforward=ff,
speed=CS.vEgo,
@ -87,7 +87,7 @@ class LatControlTorque(LatControl):
pid_log.output = float(-output_torque)
pid_log.actualLateralAccel = float(actual_lateral_accel)
pid_log.desiredLateralAccel = float(desired_lateral_accel)
pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited))
pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited_by_controls, curvature_limited))
# TODO left is positive in this convention
return -output_torque, 0.0, pid_log

@ -33,7 +33,15 @@ class TestLatControl:
lp = generate_livePose()
pose = Pose.from_live_pose(lp.livePose)
# Saturate for curvature limited and controller limited
for _ in range(1000):
_, _, lac_log = controller.update(True, CS, VM, params, False, 1, pose)
_, _, lac_log = controller.update(True, CS, VM, params, False, 0, pose, True)
assert lac_log.saturated
for _ in range(1000):
_, _, lac_log = controller.update(True, CS, VM, params, False, 0, pose, False)
assert not lac_log.saturated
for _ in range(1000):
_, _, lac_log = controller.update(True, CS, VM, params, False, 1, pose, False)
assert lac_log.saturated

@ -328,11 +328,11 @@ class SelfdriveD:
if lac.active and not recent_steer_pressed and not self.CP.notCar:
clipped_speed = max(CS.vEgo, MIN_LATERAL_CONTROL_SPEED)
actual_lateral_accel = controlstate.curvature * (clipped_speed**2)
desired_lateral_accel = controlstate.desiredCurvature * (clipped_speed**2)
desired_lateral_accel = self.sm['modelV2'].action.desiredCurvature * (clipped_speed**2)
undershooting = abs(desired_lateral_accel) / abs(1e-3 + actual_lateral_accel) > 1.2
turning = abs(desired_lateral_accel) > 1.0
good_speed = CS.vEgo > 5
if undershooting and turning and good_speed and lac.saturated:
# TODO: lac.saturated includes speed and other checks, should be pulled out
if undershooting and turning and lac.saturated:
self.events.add(EventName.steerSaturated)
# Check for FCW

@ -358,6 +358,7 @@ def migrate_cameraStates(msgs):
new_msg = messaging.new_message(msg.which())
new_camera_state = getattr(new_msg, new_msg.which())
new_camera_state.sensor = camera_state.sensor
new_camera_state.frameId = encode_id
new_camera_state.encodeId = encode_id
# timestampSof was added later so it might be missing on some old segments

@ -19,8 +19,8 @@ from openpilot.tools.lib.framereader import FrameReader, NumpyFrameReader
from openpilot.tools.lib.logreader import LogReader, save_log
from openpilot.tools.lib.github_utils import GithubUtils
TEST_ROUTE = "2f4452b03ccb98f0|2022-12-03--13-45-30"
SEGMENT = 6
TEST_ROUTE = "8494c69d3c710e81|000001d4--2648a9a404"
SEGMENT = 4
MAX_FRAMES = 100 if PC else 400
NO_MODEL = "NO_MODEL" in os.environ
@ -66,6 +66,8 @@ def generate_report(proposed, master, tmp, commit):
(lambda x: get_idx_if_non_empty(x.action.desiredCurvature), "desiredCurvature"),
(lambda x: get_idx_if_non_empty(x.leadsV3[0].x, 0), "leadsV3.x"),
(lambda x: get_idx_if_non_empty(x.laneLines[1].y, 0), "laneLines.y"),
(lambda x: get_idx_if_non_empty(x.meta.desireState, 3), "desireState.laneChangeLeft"),
(lambda x: get_idx_if_non_empty(x.meta.desireState, 4), "desireState.laneChangeRight"),
(lambda x: get_idx_if_non_empty(x.meta.disengagePredictions.gasPressProbs, 1), "gasPressProbs")
], "modelV2")
DriverStateV2_Plots = zl([
@ -143,7 +145,8 @@ def trim_logs_to_max_frames(logs, max_frames, frs_types, include_all_types):
def model_replay(lr, frs):
# modeld is using frame pairs
modeld_logs = trim_logs_to_max_frames(lr, MAX_FRAMES, {"roadCameraState", "wideRoadCameraState"}, {"roadEncodeIdx", "wideRoadEncodeIdx", "carParams"})
modeld_logs = trim_logs_to_max_frames(lr, MAX_FRAMES, {"roadCameraState", "wideRoadCameraState"},
{"roadEncodeIdx", "wideRoadEncodeIdx", "carParams", "carState", "carControl"})
dmodeld_logs = trim_logs_to_max_frames(lr, MAX_FRAMES, {"driverCameraState"}, {"driverEncodeIdx", "carParams"})
if not SEND_EXTRA_INPUTS:

@ -580,7 +580,7 @@ CONFIGS = [
),
ProcessConfig(
proc_name="modeld",
pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState", "carState"],
pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState", "carState", "carControl"],
subs=["modelV2", "drivingModelData", "cameraOdometry"],
ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime", "drivingModelData.frameDropPerc", "drivingModelData.modelExecutionTime"],
should_recv_callback=ModeldCameraSyncRcvCallback(),

@ -1 +1 @@
d343af55506b14a4011bfe43b2a49c7e3c387d75
a9487c6a5c2f0bb83c9d629ff64c8f64a4e4ca13

@ -12,10 +12,9 @@ from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, FAKE
check_openpilot_enabled, check_most_messages_valid, get_custom_params_from_lr
from openpilot.selfdrive.test.process_replay.vision_meta import DRIVER_CAMERA_FRAME_SIZES
from openpilot.selfdrive.test.update_ci_routes import upload_route
from openpilot.tools.lib.route import Route
from openpilot.tools.lib.framereader import FrameReader, BaseFrameReader, FrameType
from openpilot.tools.lib.logreader import LogReader, LogIterable, save_log
from openpilot.tools.lib.openpilotci import get_url
class DummyFrameReader(BaseFrameReader):
def __init__(self, w: int, h: int, frame_count: int, pix_val: int):
@ -55,45 +54,28 @@ def regen_segment(
def setup_data_readers(
route: str, sidx: int, use_route_meta: bool,
needs_driver_cam: bool = True, needs_road_cam: bool = True, dummy_driver_cam: bool = False
route: str, sidx: int, needs_driver_cam: bool = True, needs_road_cam: bool = True, dummy_driver_cam: bool = False
) -> tuple[LogReader, dict[str, Any]]:
if use_route_meta:
r = Route(route)
lr = LogReader(r.log_paths()[sidx])
frs = {}
if needs_road_cam and len(r.camera_paths()) > sidx and r.camera_paths()[sidx] is not None:
frs['roadCameraState'] = FrameReader(r.camera_paths()[sidx])
if needs_road_cam and len(r.ecamera_paths()) > sidx and r.ecamera_paths()[sidx] is not None:
frs['wideRoadCameraState'] = FrameReader(r.ecamera_paths()[sidx])
if needs_driver_cam:
if dummy_driver_cam:
frs['driverCameraState'] = DummyFrameReader.zero_dcamera()
elif len(r.dcamera_paths()) > sidx and r.dcamera_paths()[sidx] is not None:
device_type = next(str(msg.initData.deviceType) for msg in lr if msg.which() == "initData")
assert device_type != "neo", "Driver camera not supported on neo segments. Use dummy dcamera."
frs['driverCameraState'] = FrameReader(r.dcamera_paths()[sidx])
else:
lr = LogReader(f"{route}/{sidx}/r")
frs = {}
if needs_road_cam:
frs['roadCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc")
if next((True for m in lr if m.which() == "wideRoadCameraState"), False):
frs['wideRoadCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/ecamera.hevc")
if needs_driver_cam:
if dummy_driver_cam:
frs['driverCameraState'] = DummyFrameReader.zero_dcamera()
else:
device_type = next(str(msg.initData.deviceType) for msg in lr if msg.which() == "initData")
assert device_type != "neo", "Driver camera not supported on neo segments. Use dummy dcamera."
frs['driverCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/dcamera.hevc")
lr = LogReader(f"{route}/{sidx}/r")
frs = {}
if needs_road_cam:
frs['roadCameraState'] = FrameReader(get_url(route, str(sidx), "fcamera.hevc"))
if next((True for m in lr if m.which() == "wideRoadCameraState"), False):
frs['wideRoadCameraState'] = FrameReader(get_url(route, str(sidx), "ecamera.hevc"))
if needs_driver_cam:
if dummy_driver_cam:
frs['driverCameraState'] = DummyFrameReader.zero_dcamera()
else:
device_type = next(str(msg.initData.deviceType) for msg in lr if msg.which() == "initData")
assert device_type != "neo", "Driver camera not supported on neo segments. Use dummy dcamera."
frs['driverCameraState'] = FrameReader(get_url(route, str(sidx), "dcamera.hevc"))
return lr, frs
def regen_and_save(
route: str, sidx: int, processes: str | Iterable[str] = "all", outdir: str = FAKEDATA,
upload: bool = False, use_route_meta: bool = False, disable_tqdm: bool = False, dummy_driver_cam: bool = False
upload: bool = False, disable_tqdm: bool = False, dummy_driver_cam: bool = False
) -> str:
if not isinstance(processes, str) and not hasattr(processes, "__iter__"):
raise ValueError("whitelist_proc must be a string or iterable")
@ -110,7 +92,7 @@ def regen_and_save(
replayed_processes = CONFIGS
all_vision_pubs = {pub for cfg in replayed_processes for pub in cfg.vision_pubs}
lr, frs = setup_data_readers(route, sidx, use_route_meta,
lr, frs = setup_data_readers(route, sidx,
needs_driver_cam="driverCameraState" in all_vision_pubs,
needs_road_cam="roadCameraState" in all_vision_pubs or "wideRoadCameraState" in all_vision_pubs,
dummy_driver_cam=dummy_driver_cam)

@ -17,7 +17,7 @@ def regen_job(segment, upload, disable_tqdm):
sn = SegmentName(segment[1])
fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for _ in range(11))
try:
relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False,
relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload,
outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm, dummy_driver_cam=True)
relr = '|'.join(relr.split('/')[-2:])
return f' ("{segment[0]}", "{relr}"), '

@ -42,22 +42,22 @@ source_segments = [
segments = [
("BODY", "regenA67A128BCD8|2024-08-30--02-36-22--0"),
("HYUNDAI", "regen9CBD921E93E|2024-08-30--02-38-51--0"),
("HYUNDAI", "regenCCD47FEBC0C|2025-03-04--03-21-48--0"),
("HYUNDAI2", "regen306779F6870|2024-10-03--04-03-23--0"),
("TOYOTA", "regen1CA7A48E6F7|2024-08-30--02-45-08--0"),
("TOYOTA", "regen4A5115B248D|2025-03-04--03-21-43--0"),
("TOYOTA2", "regen6E484EDAB96|2024-08-30--02-47-37--0"),
("TOYOTA3", "regen4CE950B0267|2024-08-30--02-51-30--0"),
("HONDA", "regenC8F0D6ADC5C|2024-08-30--02-54-01--0"),
("HONDA", "regenB8CABEC09CC|2025-03-04--03-32-55--0"),
("HONDA2", "regen4B38A7428CD|2024-08-30--02-56-31--0"),
("CHRYSLER", "regenF3DBBA9E8DF|2024-08-30--02-59-03--0"),
("RAM", "regenDB02684E00A|2024-08-30--03-02-54--0"),
("SUBARU", "regenAA1FF48CF1F|2024-08-30--03-06-45--0"),
("SUBARU", "regen5E3347D0A0F|2025-03-04--03-23-55--0"),
("GM", "regen720F2BA4CF6|2024-08-30--03-09-15--0"),
("GM2", "regen9ADBECBCD1C|2024-08-30--03-13-04--0"),
("NISSAN", "regen58464878D07|2024-08-30--03-15-31--0"),
("VOLKSWAGEN", "regenED976DEB757|2024-08-30--03-18-02--0"),
("MAZDA", "regenACF84CCF482|2024-08-30--03-21-55--0"),
("FORD", "regen756F8230C21|2024-11-07--00-08-24--0"),
("FORD", "regenA75209BD115|2025-03-04--03-23-53--0"),
("RIVIAN", "bc095dc92e101734|000000db--ee9fe46e57--1"),
]

@ -1,8 +1,6 @@
import math
import json
import os
import pathlib
import psutil
import pytest
import shutil
import subprocess
@ -12,7 +10,7 @@ from collections import Counter, defaultdict
from pathlib import Path
from tabulate import tabulate
from cereal import car, log
from cereal import log
import cereal.messaging as messaging
from cereal.services import SERVICE_LIST
from openpilot.common.basedir import BASEDIR
@ -23,6 +21,7 @@ from openpilot.selfdrive.test.helpers import set_params_enabled, release_only
from openpilot.system.hardware import HARDWARE
from openpilot.system.hardware.hw import Paths
from openpilot.tools.lib.logreader import LogReader
from openpilot.tools.lib.log_time_series import msgs_to_time_series
"""
CPU usage budget
@ -112,6 +111,7 @@ def cputime_total(ct):
@pytest.mark.tici
@pytest.mark.skip_tici_setup
class TestOnroad:
@classmethod
@ -119,7 +119,8 @@ class TestOnroad:
if "DEBUG" in os.environ:
segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog.zst")), Path(Paths.log_root()).iterdir())
segs = sorted(segs, key=lambda x: x.stat().st_mtime)
cls.lr = list(LogReader(os.path.join(segs[-3], "rlog.zst")))
cls.lr = list(LogReader(os.path.join(segs[-1], "rlog.zst")))
cls.ts = msgs_to_time_series(cls.lr)
return
# setup env
@ -140,44 +141,31 @@ class TestOnroad:
proc = subprocess.Popen(["python", manager_path])
sm = messaging.SubMaster(['carState'])
with Timeout(150, "controls didn't start"):
while sm.recv_frame['carState'] < 0:
with Timeout(30, "controls didn't start"):
while not sm.seen['carState']:
sm.update(1000)
route = None
cls.segments = []
with Timeout(300, "timed out waiting for logs"):
while route is None:
route = params.get("CurrentRoute", encoding="utf-8")
time.sleep(0.01)
route = params.get("CurrentRoute", encoding="utf-8")
assert route is not None
# test car params caching
params.put("CarParamsCache", car.CarParams().to_bytes())
while len(cls.segments) < 1:
segs = set()
if Path(Paths.log_root()).exists():
segs = set(Path(Paths.log_root()).glob(f"{route}--*"))
cls.segments = sorted(segs, key=lambda s: int(str(s).rsplit('--')[-1]))
time.sleep(0.01)
segs = list(Path(Paths.log_root()).glob(f"{route}--*"))
assert len(segs) == 1
time.sleep(TEST_DURATION)
finally:
cls.gpu_procs = {psutil.Process(int(f.name)).name() for f in pathlib.Path('/sys/devices/virtual/kgsl/kgsl/proc/').iterdir() if f.is_dir()}
if proc is not None:
proc.terminate()
if proc.wait(60) is None:
proc.kill()
cls.lrs = [list(LogReader(os.path.join(str(s), "rlog.zst"))) for s in cls.segments]
cls.lr = list(LogReader(os.path.join(str(cls.segments[0]), "rlog.zst")))
cls.log_path = cls.segments[0]
cls.lr = list(LogReader(os.path.join(str(segs[0]), "rlog.zst")))
st = time.monotonic()
cls.ts = msgs_to_time_series(cls.lr)
print("msgs to time series", time.monotonic() - st)
log_path = segs[0]
cls.log_sizes = {}
for f in cls.log_path.iterdir():
for f in log_path.iterdir():
assert f.is_file()
cls.log_sizes[f] = f.stat().st_size / 1e6
@ -198,7 +186,7 @@ class TestOnroad:
assert len(msgs) >= math.floor(SERVICE_LIST[s].frequency*int(TEST_DURATION*0.8))
def test_manager_starting_time(self):
st = self.msgs['managerState'][0].logMonoTime / 1e9
st = self.ts['managerState']['t'][0]
assert (st - self.manager_st) < 10, f"manager.py took {st - self.manager_st}s to publish the first 'managerState' msg"
def test_cloudlog_size(self):
@ -226,7 +214,7 @@ class TestOnroad:
result += "-------------- UI Draw Timing ------------------\n"
result += "------------------------------------------------\n"
ts = [m.uiDebug.drawTimeMillis for m in self.msgs['uiDebug']]
ts = self.ts['uiDebug']['drawTimeMillis']
result += f"min {min(ts):.2f}ms\n"
result += f"max {max(ts):.2f}ms\n"
result += f"std {np.std(ts):.2f}ms\n"
@ -309,9 +297,6 @@ class TestOnroad:
assert np.max(np.diff(mems)) <= 4, "Max memory increase too high"
assert np.average(np.diff(mems)) <= 1, "Average memory increase too high"
def test_gpu_usage(self):
assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld", "selfdrive.modeld.dmonitoringmodeld"}
def test_camera_frame_timings(self, subtests):
# test timing within a single camera
result = "\n"
@ -319,7 +304,7 @@ class TestOnroad:
result += "----------------- SOF Timing ------------------\n"
result += "------------------------------------------------\n"
for name in ['roadCameraState', 'wideRoadCameraState', 'driverCameraState']:
ts = [getattr(m, m.which()).timestampSof for m in self.lr if name in m.which()]
ts = self.ts[name]['timestampSof']
d_ms = np.diff(ts) / 1e6
d50 = np.abs(d_ms-50)
result += f"{name} sof delta vs 50ms: min {min(d50):.2f}ms\n"
@ -338,35 +323,51 @@ class TestOnroad:
# sanity checks within a single cam
for cam in cams:
with subtests.test(test="frame_skips", camera=cam):
cam_log = [getattr(x, x.which()) for x in self.msgs[cam]]
assert set(np.diff([x.frameId for x in cam_log])) == {1, }, "Frame ID skips"
assert set(np.diff(self.ts[cam]['frameId'])) == {1, }, "Frame ID skips"
# EOF > SOF
eof_sof_diff = np.array([x.timestampEof - x.timestampSof for x in cam_log])
eof_sof_diff = self.ts[cam]['timestampEof'] - self.ts[cam]['timestampSof']
assert np.all(eof_sof_diff > 0)
assert np.all(eof_sof_diff < 50*1e6)
fid = {c: [getattr(m, m.which()).frameId for m in self.msgs[c]] for c in cams}
first_fid = [min(x) for x in fid.values()]
first_fid = {c: min(self.ts[c]['frameId']) for c in cams}
if cam.endswith('CameraState'):
# camerad guarantees that all cams start on frame ID 0
# (note loggerd also needs to start up fast enough to catch it)
assert set(first_fid) == {0, }, "Cameras don't start on frame ID 0"
assert set(first_fid.values()) == {0, }, "Cameras don't start on frame ID 0"
else:
# encoder guarantees all cams start on the same frame ID
assert len(set(first_fid)) == 1, "Cameras don't start on same frame ID"
assert len(set(first_fid.values())) == 1, "Cameras don't start on same frame ID"
# we don't do a full segment rotation, so these might not match exactly
last_fid = [max(x) for x in fid.values()]
assert max(last_fid) - min(last_fid) < 10
last_fid = {c: max(self.ts[c]['frameId']) for c in cams}
assert max(last_fid.values()) - min(last_fid.values()) < 10
start, end = min(first_fid), min(last_fid)
all_ts = [[getattr(m, m.which()).timestampSof for m in self.msgs[c]] for c in cams]
start, end = min(first_fid.values()), min(last_fid.values())
for i in range(end-start):
ts = [round(x[i]/1e6, 1) for x in all_ts]
diff = max(ts) - min(ts)
ts = {c: round(self.ts[c]['timestampSof'][i]/1e6, 1) for c in cams}
diff = (max(ts.values()) - min(ts.values()))
assert diff < 2, f"Cameras not synced properly: frame_id={start+i}, {diff=:.1f}ms, {ts=}"
def test_camera_encoder_matches(self, subtests):
# sanity check that the frame metadata is consistent with the encoded frames
pairs = [('roadCameraState', 'roadEncodeIdx'),
('wideRoadCameraState', 'wideRoadEncodeIdx'),
('driverCameraState', 'driverEncodeIdx')]
for cam, enc in pairs:
with subtests.test(camera=cam, encoder=enc):
cam_frames = {fid: (sof, eof) for fid, sof, eof in zip(
self.ts[cam]['frameId'],
self.ts[cam]['timestampSof'],
self.ts[cam]['timestampEof'],
strict=True,
)}
for i, fid in enumerate(self.ts[enc]['frameId']):
cam_sof, cam_eof = cam_frames[fid]
enc_sof, enc_eof = self.ts[enc]['timestampSof'][i], self.ts[enc]['timestampEof'][i]
assert enc_sof == cam_sof, f"SOF mismatch: frameId={fid}, enc_sof={enc_sof}, cam_sof={cam_sof}"
assert enc_eof == cam_eof, f"EOF mismatch: frameId={fid}, enc_eof={enc_eof}, cam_eof={cam_eof}"
def test_mpc_execution_timings(self):
result = "\n"
result += "------------------------------------------------\n"
@ -438,12 +439,7 @@ class TestOnroad:
@release_only
def test_startup(self):
startup_alert = None
for msg in self.lrs[0]:
# can't use onroadEvents because the first msg can be dropped while loggerd is starting up
if msg.which() == "selfdriveState":
startup_alert = msg.selfdriveState.alertText1
break
startup_alert = self.ts['selfdriveState']['alertText1'][0]
expected = EVENTS[log.OnroadEvent.EventName.startup][ET.PERMANENT].alert_text_1
assert startup_alert == expected, "wrong startup alert"

@ -10,6 +10,9 @@
#include <QScrollArea>
#include <QStackedLayout>
#include <QProgressBar>
#include <QJsonDocument>
#include <QJsonObject>
#include <QTimer>
FirehosePanel::FirehosePanel(SettingsWindow *parent) : QWidget((QWidget*)parent) {
layout = new QVBoxLayout(this);
@ -28,7 +31,7 @@ FirehosePanel::FirehosePanel(SettingsWindow *parent) : QWidget((QWidget*)parent)
content_layout->setSpacing(20);
// Top description
QLabel *description = new QLabel(tr("openpilot learns to drive by watching humans, like you, drive.\n\nFirehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models with better Experimental Mode."));
QLabel *description = new QLabel(tr("openpilot learns to drive by watching humans, like you, drive.\n\nFirehose Mode allows you to maximize your training data uploads to improve openpilot's driving models. More data means bigger models, which means better Experimental Mode."));
description->setStyleSheet("font-size: 45px; padding-bottom: 20px;");
description->setWordWrap(true);
content_layout->addWidget(description);
@ -40,41 +43,16 @@ FirehosePanel::FirehosePanel(SettingsWindow *parent) : QWidget((QWidget*)parent)
line->setStyleSheet("background-color: #444444; margin-top: 5px; margin-bottom: 5px;");
content_layout->addWidget(line);
enable_firehose = new ParamControl("FirehoseMode", tr("Enable Firehose Mode"), "", "");
toggle_label = new QLabel(tr("Firehose Mode: ACTIVE"));
toggle_label->setStyleSheet("font-size: 60px; font-weight: bold; color: white;");
content_layout->addWidget(toggle_label);
content_layout->addWidget(enable_firehose);
// Create progress bar container
progress_container = new QFrame();
progress_container->hide();
QHBoxLayout *progress_layout = new QHBoxLayout(progress_container);
progress_layout->setContentsMargins(10, 0, 10, 10);
progress_layout->setSpacing(20);
progress_bar = new QProgressBar();
progress_bar->setRange(0, 100);
progress_bar->setValue(0);
progress_bar->setTextVisible(false);
progress_bar->setStyleSheet(R"(
QProgressBar {
background-color: #444444;
border-radius: 10px;
height: 20px;
}
QProgressBar::chunk {
background-color: #3498db;
border-radius: 10px;
}
)");
progress_bar->setFixedHeight(40);
// Progress text
progress_text = new QLabel(tr("0%"));
progress_text->setStyleSheet("font-size: 40px; font-weight: bold; color: white;");
progress_layout->addWidget(progress_text);
content_layout->addWidget(progress_container);
// Add contribution label
contribution_label = new QLabel();
contribution_label->setStyleSheet("font-size: 52px; margin-top: 10px; margin-bottom: 10px;");
contribution_label->setWordWrap(true);
contribution_label->hide();
content_layout->addWidget(contribution_label);
// Add a separator before detailed instructions
QFrame *line2 = new QFrame();
@ -85,22 +63,49 @@ FirehosePanel::FirehosePanel(SettingsWindow *parent) : QWidget((QWidget*)parent)
// Detailed instructions at the bottom
detailed_instructions = new QLabel(tr(
"Follow these steps to get your device ready:<br>"
"\t1. Bring your device inside and connect to a good USB-C adapter<br>"
"\t2. Connect to Wi-Fi<br>"
"\t3. Enable the toggle<br>"
"\t4. Leave it connected for at least 30 minutes<br>"
"For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.<br>"
"<br>"
"The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness."
"<br><br><b>FAQ</b><br>"
"<i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br>"
"<i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br>"
"<i>Do I need to be on Wi-Fi?</i> Yes.<br>"
"<i>Do I need to bring the device inside?</i> No, you can enable once you're parked, however your uploads will be limited by your car's battery.<br>"
"Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.<br>"
"<br><br>"
"<b>Frequently Asked Questions</b><br><br>"
"<i>Does it matter how or where I drive?</i> Nope, just drive as you normally would.<br><br>"
"<i>What's a good USB-C adapter?</i> Any fast phone or laptop charger should be fine.<br><br>"
"<i>Does it matter which software I run?</i> Yes, only upstream openpilot (and particular forks) are able to be used for training."
));
detailed_instructions->setStyleSheet("font-size: 40px; padding: 20px; color: #E4E4E4;");
detailed_instructions->setStyleSheet("font-size: 40px; color: #E4E4E4;");
detailed_instructions->setWordWrap(true);
content_layout->addWidget(detailed_instructions);
layout->addWidget(content, 1);
// Set up the API request for firehose stats
const QString dongle_id = QString::fromStdString(Params().get("DongleId"));
firehose_stats = new RequestRepeater(this, CommaApi::BASE_URL + "/v1/devices/" + dongle_id + "/firehose_stats",
"ApiCache_FirehoseStats", 30, true);
QObject::connect(firehose_stats, &RequestRepeater::requestDone, [=](const QString &response, bool success) {
if (success) {
QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8());
QJsonObject json = doc.object();
int count = json["firehose"].toInt();
contribution_label->setText(tr("<b>%1 %2</b> of your driving are in the training dataset so far.").arg(count).arg(count == 1 ? "segment" : "segments"));
contribution_label->show();
}
});
QObject::connect(uiState(), &UIState::uiUpdate, this, &FirehosePanel::refresh);
}
void FirehosePanel::refresh() {
auto deviceState = (*uiState()->sm)["deviceState"].getDeviceState();
auto networkType = deviceState.getNetworkType();
bool networkMetered = deviceState.getNetworkMetered();
bool is_active = !networkMetered && (networkType != cereal::DeviceState::NetworkType::NONE);
if (is_active) {
toggle_label->setText(tr("ACTIVE"));
toggle_label->setStyleSheet("font-size: 60px; font-weight: bold; color: #2ecc71;");
} else {
toggle_label->setText(tr("<span stylesheet='font-size: 60px; font-weight: bold; color: #e74c3c;'>INACTIVE</span>: connect to unmetered network"));
toggle_label->setStyleSheet("font-size: 60px;");
}
}

@ -2,10 +2,8 @@
#include <QWidget>
#include <QVBoxLayout>
#include <QProgressBar>
#include <QLabel>
#include "selfdrive/ui/qt/widgets/controls.h"
#include "common/params.h"
#include "selfdrive/ui/qt/request_repeater.h"
// Forward declarations
class SettingsWindow;
@ -17,12 +15,13 @@ public:
private:
QVBoxLayout *layout;
ParamControl *enable_firehose;
QFrame *progress_container;
QProgressBar *progress_bar;
QLabel *progress_text;
QLabel *detailed_instructions;
void updateFirehoseState(bool enabled);
QLabel *contribution_label;
QLabel *toggle_label;
RequestRepeater *firehose_stats;
private slots:
void refresh();
};

@ -312,21 +312,29 @@
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>

@ -312,21 +312,29 @@
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>

@ -312,21 +312,29 @@
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>

@ -312,21 +312,29 @@
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>

@ -311,25 +311,31 @@
<source>🔥 Firehose Mode 🔥</source>
<translation>🔥 Firehoseモード 🔥</translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<translation>Firehoseを有効にする</translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<translation>openpilotは人間であるあなたの運転から学びAI学習します
Firehoseモードを有効にするとopenpilotの運転モデルを向上させることができますExperimentalモードの精度向上につながります</translation>
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<translation>:&lt;br&gt; 1. USB-C電源に接続してください&lt;br&gt; 2. Wi-Fiに接続してください&lt;br&gt; 3. &lt;br&gt; 4. 30&lt;br&gt;&lt;br&gt;1&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;どのように運転するか、どこで運転するかは重要ですか?&lt;/i&gt; &lt;br&gt;&lt;i&gt;USB-C電源とは何ですか&lt;/i&gt; スマフォやノートPC用のワット数の大きい充電器を使って下さい。&lt;br&gt;&lt;i&gt;Wi-Fiに接続する必要がありますか?&lt;/i&gt; &lt;br&gt;&lt;i&gt;&lt;/i&gt; &lt;br&gt;</translation>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>

@ -311,25 +311,31 @@
<source>🔥 Firehose Mode 🔥</source>
<translation>🔥 🔥</translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<translation> </translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<translation> .
. .</translation>
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation>0%</translation>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<translation> .:&lt;br&gt; 1. USB-C .&lt;br&gt; 2. Wi-Fi에 .&lt;br&gt; 3. .&lt;br&gt; 4. 30 .&lt;br&gt;&lt;br&gt; . .&lt;br&gt;&lt;br&gt;&lt;b&gt; &lt;/b&gt;&lt;br&gt;&lt;i&gt;운전 방법이나 장소가 중요한가요?&lt;/i&gt; , .&lt;br&gt;&lt;i&gt; USB-C ?&lt;/i&gt; 휴대폰이나 노트북 고속 충전기라면 어떤 것이든 괜찮습니다.&lt;br&gt;&lt;i&gt;Wi-Fi에 연결되어 있어야 하나요?&lt;/i&gt; .&lt;br&gt;&lt;i&gt; ?&lt;/i&gt; , .&lt;br&gt;</translation>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>

@ -309,24 +309,32 @@
<name>FirehosePanel</name>
<message>
<source>🔥 Firehose Mode 🔥</source>
<translation>🔥 Mode Firehose 🔥</translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>
@ -668,7 +676,7 @@ Isso pode levar até um minuto.</translation>
</message>
<message>
<source>Firehose</source>
<translation type="unfinished"></translation>
<translation>Firehose</translation>
</message>
</context>
<context>
@ -1146,15 +1154,15 @@ Isso pode levar até um minuto.</translation>
<name>WiFiPromptWidget</name>
<message>
<source>Open</source>
<translation type="unfinished"></translation>
<translation>Abrir</translation>
</message>
<message>
<source>Maximize your training data uploads to improve openpilot&apos;s driving models.</source>
<translation type="unfinished"></translation>
<translation>Maximize seus envios de dados de treinamento para melhorar os modelos de direção do openpilot.</translation>
</message>
<message>
<source>&lt;span style=&apos;font-family: &quot;Noto Color Emoji&quot;;&apos;&gt;🔥&lt;/span&gt; Firehose Mode &lt;span style=&apos;font-family: Noto Color Emoji;&apos;&gt;🔥&lt;/span&gt;</source>
<translation type="unfinished"></translation>
<translation>&lt;span style=&apos;font-family: &quot;Noto Color Emoji&quot;;&apos;&gt;🔥&lt;/span&gt; Mode Firehose &lt;span style=&apos;font-family: Noto Color Emoji;&apos;&gt;🔥&lt;/span&gt;</translation>
</message>
</context>
<context>

@ -312,21 +312,29 @@
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>

@ -312,21 +312,29 @@
<translation type="unfinished"></translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation type="unfinished">5G {0%?}</translation>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>

@ -311,25 +311,31 @@
<source>🔥 Firehose Mode 🔥</source>
<translation>🔥 🔥</translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<translation></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<translation>openpilot
openpilot </translation>
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation>0%</translation>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<translation>&lt;br&gt; 1. USB-C &lt;br&gt; 2. Wi-Fi&lt;br&gt; 3. &lt;br&gt; 4. 30 &lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;&lt;/b&gt;&lt;br&gt;&lt;i&gt;驾驶方式或地点重要吗?&lt;/i&gt; &lt;br&gt;&lt;i&gt; USB-C &lt;/i&gt; 任何快速手机或笔记本电脑充电器都可以。&lt;br&gt;&lt;i&gt;我需要连接 Wi-Fi 吗?&lt;/i&gt; &lt;br&gt;&lt;i&gt;&lt;/i&gt; &lt;br&gt;</translation>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>

@ -311,25 +311,31 @@
<source>🔥 Firehose Mode 🔥</source>
<translation>🔥 🔥</translation>
</message>
<message>
<source>Enable Firehose Mode</source>
<translation></translation>
</message>
<message>
<source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models with better Experimental Mode.</source>
<translation>openpilot
openpilot </translation>
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>&lt;b&gt;%1 %2&lt;/b&gt; of your driving are in the training dataset so far.</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>0%</source>
<translation>0%</translation>
<source>ACTIVE</source>
<translation type="unfinished"></translation>
</message>
<message>
<source>Follow these steps to get your device ready:&lt;br&gt; 1. Bring your device inside and connect to a good USB-C adapter&lt;br&gt; 2. Connect to Wi-Fi&lt;br&gt; 3. Enable the toggle&lt;br&gt; 4. Leave it connected for at least 30 minutes&lt;br&gt;&lt;br&gt;The toggle turns off once you restart your device. Repeat at least once a week for maximum effectiveness.&lt;br&gt;&lt;br&gt;&lt;b&gt;FAQ&lt;/b&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;i&gt;Do I need to be on Wi-Fi?&lt;/i&gt; Yes.&lt;br&gt;&lt;i&gt;Do I need to bring the device inside?&lt;/i&gt; No, you can enable once you&apos;re parked, however your uploads will be limited by your car&apos;s battery.&lt;br&gt;</source>
<translation>&lt;br&gt; 1. USB-C &lt;br&gt; 2. Wi-Fi&lt;br&gt; 3. &lt;br&gt; 4. 30 &lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;&lt;/b&gt;&lt;br&gt;&lt;i&gt;駕駛方式或地點重要嗎?&lt;/i&gt; &lt;br&gt;&lt;i&gt; USB-C &lt;/i&gt; 任何快速手機或筆記本電腦充電器都可以。&lt;br&gt;&lt;i&gt;我需要連接 Wi-Fi 嗎?&lt;/i&gt; &lt;br&gt;&lt;i&gt;&lt;/i&gt; &lt;br&gt;</translation>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to unmetered network</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>

@ -508,10 +508,6 @@ def getSshAuthorizedKeys() -> str:
def getGithubUsername() -> str:
return Params().get("GithubUsername", encoding='utf8') or ''
@dispatcher.add_method
def getFirehoseMode() -> bool:
return Params().get_bool("FirehoseMode") or False
@dispatcher.add_method
def getSimInfo():
return HARDWARE.get_sim_info()

@ -67,17 +67,17 @@
},
{
"name": "system",
"url": "https://commadist.azureedge.net/agnosupdate/system-061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75.img.xz",
"hash": "affcc08700026f1726ef16337e031fffc5556435b2b0facea81c7ffb0b66560c",
"hash_raw": "061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75",
"url": "https://commadist.azureedge.net/agnosupdate/system-5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9.img.xz",
"hash": "e4872f4132111b7b28586d978dd01bb48ffa031e103d029ebede7613c1bc2aa6",
"hash_raw": "5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9",
"size": 4404019200,
"sparse": true,
"full_check": false,
"has_ab": true,
"ondevice_hash": "cc86836c6fc1c54f24dd0395e57e0b1ac6efe44d3ece833ab3ed456fe46a55cf",
"ondevice_hash": "4e5e680b4ac387ddc974b32dd3d5ec1d76282511eab974866b3b72399034985e",
"alt": {
"hash": "061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75",
"url": "https://commadist.azureedge.net/agnosupdate/system-061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75.img",
"hash": "5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9",
"url": "https://commadist.azureedge.net/agnosupdate/system-5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9.img",
"size": 4404019200
}
}

@ -350,51 +350,51 @@
},
{
"name": "system",
"url": "https://commadist.azureedge.net/agnosupdate/system-061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75.img.xz",
"hash": "affcc08700026f1726ef16337e031fffc5556435b2b0facea81c7ffb0b66560c",
"hash_raw": "061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75",
"url": "https://commadist.azureedge.net/agnosupdate/system-5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9.img.xz",
"hash": "e4872f4132111b7b28586d978dd01bb48ffa031e103d029ebede7613c1bc2aa6",
"hash_raw": "5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9",
"size": 4404019200,
"sparse": true,
"full_check": false,
"has_ab": true,
"ondevice_hash": "cc86836c6fc1c54f24dd0395e57e0b1ac6efe44d3ece833ab3ed456fe46a55cf",
"ondevice_hash": "4e5e680b4ac387ddc974b32dd3d5ec1d76282511eab974866b3b72399034985e",
"alt": {
"hash": "061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75",
"url": "https://commadist.azureedge.net/agnosupdate/system-061783c4826369c7aa711266e8e1d9eecfd0a6d6c8afc6042e4045617512be75.img",
"hash": "5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9",
"url": "https://commadist.azureedge.net/agnosupdate/system-5612484e7f255659c0845de620e7c733afd2e1b939f9464f5ef039721bb7cba9.img",
"size": 4404019200
}
},
{
"name": "userdata_90",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_90-fd9d27a3ef5c1f63b85721798ba4ea10f2a4c71d0c8d9b59362a99f24dfff54a.img.xz",
"hash": "b77b66ae8178519dbd72443ff7bdd21b97d0d4d76425472bedc7d369958de37b",
"hash_raw": "fd9d27a3ef5c1f63b85721798ba4ea10f2a4c71d0c8d9b59362a99f24dfff54a",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_90-16c037fa42ee99bc6ec92909efc8a8075a0e8a0232a7d90e39e7d40a7bd0ee8e.img.xz",
"hash": "c6fb215f2b297f7ff5b8f133bc5d687772b37f2fee42a44aa730e37a84a14e52",
"hash_raw": "16c037fa42ee99bc6ec92909efc8a8075a0e8a0232a7d90e39e7d40a7bd0ee8e",
"size": 96636764160,
"sparse": true,
"full_check": true,
"has_ab": false,
"ondevice_hash": "52d2b8e2486e7fa0cdeb2a6512a8058db43544c905367a2e1b81a5ad4636d4b7"
"ondevice_hash": "7199262f209abbb07be5eece505ac4d4c7ba8957f2d9ff7b1ac1ef2063461665"
},
{
"name": "userdata_89",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_89-1042711c5f69146ff7680f09eab1b2eb6fe9da0411318e9ff913c27168cb0307.img.xz",
"hash": "cc24b1c78234f92cd8ef66541f3fb8924719fc4b7f42c26e26eb71ec21cd2e93",
"hash_raw": "1042711c5f69146ff7680f09eab1b2eb6fe9da0411318e9ff913c27168cb0307",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_89-62c2c41470282b581ec1bbbe0375fb3b6c66df2f4bc3dc6c6fdf796f1797f136.img.xz",
"hash": "d66f894436fa11d4ff00f8a84e54d9e23a6492b0087f69bb958d2ab0bdc6dfba",
"hash_raw": "62c2c41470282b581ec1bbbe0375fb3b6c66df2f4bc3dc6c6fdf796f1797f136",
"size": 95563022336,
"sparse": true,
"full_check": true,
"has_ab": false,
"ondevice_hash": "80bf38b8b60ea1ef1fc0849af4e18bf114761f98f5371476e2f762d0f8463204"
"ondevice_hash": "f1d3685618f6d1bde24ce6109284c5d30ece2f4fd015be67e8b52ef7e06067a4"
},
{
"name": "userdata_30",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_30-6d429550c42616e3f252034305f238ce0e90926762992ff3f92322f226caa5b6.img.xz",
"hash": "657b052cf6434ef19ff73bdeaf5b2511e5c42f64594ae37bac467a12b4cd673f",
"hash_raw": "6d429550c42616e3f252034305f238ce0e90926762992ff3f92322f226caa5b6",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_30-3e71d8804c90a6dff5048edb976149f9ea177efa139dea47cb585cef76b26f6e.img.xz",
"hash": "1b201ecbd0e1573777811bf18fa90cb080bfbccb34a6dcfd39b412632e7ca699",
"hash_raw": "3e71d8804c90a6dff5048edb976149f9ea177efa139dea47cb585cef76b26f6e",
"size": 32212254720,
"sparse": true,
"full_check": true,
"has_ab": false,
"ondevice_hash": "6437e5a5b7144103952950f2f59f8e70b98cd26ee5bfb06cbd0a13b2e2f343b7"
"ondevice_hash": "47c28e63209556442cd9d2fd06a6c0e7fcf35c8a4e4fbcc550b9c089429ad0e0"
}
]

@ -1 +1 @@
Subproject commit 6f39c4d653737c056540194605dc18a7273df280
Subproject commit 70266e9f94d5a247ccbb2f3a46e72a2fbdaf7a8e

@ -7,7 +7,7 @@ from opendbc.car.fingerprints import MIGRATION
from opendbc.car.values import PLATFORMS
def generate_dbc_json() -> str:
def generate_dbc_dict() -> dict[str, str]:
dbc_map = {}
for platform in PLATFORMS.values():
if platform != "MOCK":
@ -24,7 +24,7 @@ def generate_dbc_json() -> str:
if MIGRATION[m] in dbc_map:
dbc_map[m] = dbc_map[MIGRATION[m]]
return json.dumps(dict(sorted(dbc_map.items())), indent=2)
return dbc_map
if __name__ == "__main__":
@ -35,5 +35,5 @@ if __name__ == "__main__":
args = parser.parse_args()
with open(args.out, 'w') as f:
f.write(generate_dbc_json())
f.write(json.dumps(dict(sorted(generate_dbc_dict().items())), indent=2))
print(f"Generated and written to {args.out}")

@ -57,7 +57,21 @@ Traceback (most recent call last):
AssertionError: 1 is not false : panda safety doesn't agree with openpilot: {'gasPressed': 116}
```
### [tools/car_porting/examples/subaru_steer_temp_fault.ipynb](/tools/car_porting/examples/subaru_steer_temp_fault.ipynb)
## Jupyter notebooks
To use these notebooks, install Jupyter within your [openpilot virtual environment](/tools/README.md).
```bash
uv pip install jupyter ipykernel
```
Launching:
```bash
jupyter notebook
```
### [examples/subaru_steer_temp_fault.ipynb](/tools/car_porting/examples/subaru_steer_temp_fault.ipynb)
An example of searching through a database of segments for a specific condition, and plotting the results.
@ -65,7 +79,7 @@ An example of searching through a database of segments for a specific condition,
*a plot of the steer_warning vs steering angle, where we can see it is clearly caused by a large steering angle change*
### [tools/car_porting/examples/subaru_long_accel.ipynb](/tools/car_porting/examples/subaru_long_accel.ipynb)
### [examples/subaru_long_accel.ipynb](/tools/car_porting/examples/subaru_long_accel.ipynb)
An example of plotting the response of an actuator when it is active.
@ -73,7 +87,7 @@ An example of plotting the response of an actuator when it is active.
*a plot of the brake_pressure vs acceleration, where we can see it is a fairly linear response.*
### [tools/car_porting/examples/ford_vin_fingerprint.ipynb](/tools/car_porting/examples/ford_vin_fingerprint.ipynb)
### [examples/ford_vin_fingerprint.ipynb](/tools/car_porting/examples/ford_vin_fingerprint.ipynb)
In this example, we use the public comma car segments database to check if vin fingerprinting is feasible for ford.
@ -94,3 +108,22 @@ vin: 5LM5J7XC8MGXXXXXX real platform: FORD EXPLORER 6TH GEN determi
vin: 3FTTW8E31PRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False
vin: 3FTTW8E99NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False
```
### [examples/find_segments_with_message.ipynb](/tools/car_porting/examples/find_segments_with_message.ipynb)
Searches for segments where a set of given CAN message IDs are present. In the example, we search for all messages
used for CAN-based ignition detection.
```
Match found: 46b21f1c5f7aa885/2024-01-23--15-19-34/20/s JEEP GRAND CHEROKEE V6 2018 ['VW CAN Ign']
Match found: a63a23c3e628f288/2023-11-05--18-36-20/8/s JEEP GRAND CHEROKEE V6 2018 ['VW CAN Ign']
Match found: ce31b7a998781ba8/2024-01-19--07-05-29/23/s JEEP GRAND CHEROKEE 2019 ['VW CAN Ign']
Match found: e1dfba62a4e33f7b/2023-12-25--19-31-00/4/s JEEP GRAND CHEROKEE 2019 ['VW CAN Ign']
Match found: e1dfba62a4e33f7b/2024-01-10--14-33-57/2/s JEEP GRAND CHEROKEE 2019 ['VW CAN Ign']
Match found: ae679616266f4096/2023-12-05--15-43-46/4/s RAM HD 5TH GEN ['Tesla 3/Y CAN Ign']
Match found: ae679616266f4096/2023-11-18--17-49-42/3/s RAM HD 5TH GEN ['Tesla 3/Y CAN Ign']
Match found: ae679616266f4096/2024-01-03--21-57-09/25/s RAM HD 5TH GEN ['Tesla 3/Y CAN Ign']
Match found: 6dae2984cc53cd7f/2023-12-10--11-53-15/17/s FORD BRONCO SPORT 1ST GEN ['Rivian CAN Ign']
Match found: 6dae2984cc53cd7f/2023-12-03--17-31-17/29/s FORD BRONCO SPORT 1ST GEN ['Rivian CAN Ign']
Match found: 6dae2984cc53cd7f/2023-11-27--23-29-07/1/s FORD BRONCO SPORT 1ST GEN ['Rivian CAN Ign']
```

@ -0,0 +1,232 @@
{
"cells": [
{
"cell_type": "code",
"execution_count": 85,
"id": "facb8edc-9924-491a-a4dd-fe6135b0c6c4",
"metadata": {},
"outputs": [],
"source": [
"# Import all cars from opendbc\n",
"\n",
"from opendbc.car import structs\n",
"from opendbc.car.values import PLATFORMS as TEST_PLATFORMS\n",
"\n",
"# Example: add additional platforms/segments to test outside of commaCarSegments\n",
"\n",
"EXTRA_SEGMENTS = {\n",
" # \"81dd9e9fe256c397/0000001f--97c42cf98d\", # Volkswagen ID.4 test route, new car port, not in public dataset\n",
"}"
]
},
{
"cell_type": "code",
"execution_count": 86,
"id": "ed1c8aec-c274-4c61-b83d-711ea194bf86",
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Searching 221 platforms\n",
"No segments available for DODGE_DURANGO\n",
"No segments available for FORD_RANGER_MK2\n",
"No segments available for HOLDEN_ASTRA\n",
"No segments available for CADILLAC_ATS\n",
"No segments available for CHEVROLET_MALIBU\n",
"No segments available for CADILLAC_XT4\n",
"No segments available for CHEVROLET_VOLT_2019\n",
"No segments available for CHEVROLET_TRAVERSE\n",
"No segments available for GMC_YUKON\n",
"No segments available for HONDA_ODYSSEY_CHN\n",
"No segments available for HYUNDAI_KONA_2022\n",
"No segments available for HYUNDAI_NEXO_1ST_GEN\n",
"No segments available for GENESIS_GV70_ELECTRIFIED_1ST_GEN\n",
"No segments available for GENESIS_G80_2ND_GEN_FL\n",
"No segments available for RIVIAN_R1_GEN1\n",
"No segments available for SUBARU_FORESTER_HYBRID\n",
"No segments available for TESLA_MODEL_3\n",
"No segments available for TESLA_MODEL_Y\n",
"No segments available for TOYOTA_RAV4_PRIME\n",
"No segments available for TOYOTA_SIENNA_4TH_GEN\n",
"No segments available for LEXUS_LC_TSS2\n",
"No segments available for VOLKSWAGEN_CADDY_MK3\n",
"No segments available for VOLKSWAGEN_CRAFTER_MK2\n",
"No segments available for VOLKSWAGEN_JETTA_MK6\n",
"Searching 577 segments\n"
]
}
],
"source": [
"import random\n",
"\n",
"from openpilot.tools.lib.logreader import LogReader\n",
"from openpilot.tools.lib.comma_car_segments import get_comma_car_segments_database\n",
"\n",
"\n",
"MAX_SEGS_PER_PLATFORM = 3 # Increase this to search more segments\n",
"\n",
"database = get_comma_car_segments_database()\n",
"TEST_SEGMENTS = []\n",
"\n",
"print(f\"Searching {len(TEST_PLATFORMS)} platforms\")\n",
"\n",
"for platform in TEST_PLATFORMS:\n",
" if platform not in database:\n",
" print(f\"No segments available for {platform}\")\n",
" continue\n",
" \n",
" all_segments = database[platform]\n",
" NUM_SEGMENTS = min(len(all_segments), MAX_SEGS_PER_PLATFORM)\n",
" TEST_SEGMENTS.extend(random.sample(all_segments, NUM_SEGMENTS))\n",
"\n",
"TEST_SEGMENTS.extend(EXTRA_SEGMENTS)\n",
"\n",
"print(f\"Searching {len(TEST_SEGMENTS)} segments\")"
]
},
{
"cell_type": "code",
"execution_count": null,
"id": "0c75e8f2-4f5f-4f89-b8db-5223a6534a9f",
"metadata": {},
"outputs": [
{
"data": {
"application/vnd.jupyter.widget-view+json": {
"model_id": "27a243c33de44498b2b946190df44b23",
"version_major": 2,
"version_minor": 0
},
"text/plain": [
"segments searched: 0%| | 0/577 [00:00<?, ?it/s]"
]
},
"metadata": {},
"output_type": "display_data"
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"Match found: 0f53b336851e1384/2023-11-20--09-44-03/12/s CHRYSLER PACIFICA HYBRID 2018 ['VW CAN Ign']\n",
"Match found: 7620ad20d3cefc64/2023-10-28--08-14-40/3/s CHRYSLER PACIFICA HYBRID 2018 ['VW CAN Ign']\n",
"Match found: 00d247a9bb1f9196/2023-11-06--13-33-17/9/s CHRYSLER PACIFICA HYBRID 2018 ['VW CAN Ign']\n",
"Match found: 120a432f63cb0de2/2023-10-30--20-01-34/1/s CHRYSLER PACIFICA HYBRID 2019 ['VW CAN Ign']\n",
"Match found: b70b56b76a6217f2/2023-12-19--08-30-22/35/s CHRYSLER PACIFICA HYBRID 2019 ['VW CAN Ign']\n",
"Match found: 97e388680a6716ed/2024-01-17--10-15-13/9/s CHRYSLER PACIFICA HYBRID 2019 ['VW CAN Ign']\n",
"Match found: 2137b01aa0ca63f9/2024-01-06--22-06-14/70/s CHRYSLER PACIFICA 2018 ['VW CAN Ign']\n",
"Match found: 8fc6a1b72c8b1357/2023-11-06--07-50-05/8/s CHRYSLER PACIFICA 2018 ['VW CAN Ign']\n",
"Match found: 7e705eb5c27a49cc/2024-01-18--16-51-20/3/s CHRYSLER PACIFICA 2018 ['VW CAN Ign']\n",
"Match found: 12208e5acdc97eb3/2024-01-20--14-46-24/12/s CHRYSLER PACIFICA 2020 ['VW CAN Ign']\n",
"Match found: 12208e5acdc97eb3/2023-11-30--12-01-09/2/s CHRYSLER PACIFICA 2020 ['VW CAN Ign']\n",
"Match found: 9cad19e0efce3650/2024-01-26--10-24-52/27/s CHRYSLER PACIFICA 2020 ['VW CAN Ign']\n",
"Match found: 9db428338427dec2/2023-11-05--18-40-09/21/s JEEP GRAND CHEROKEE V6 2018 ['VW CAN Ign']\n",
"Match found: d50ada8ee55a5e74/2023-12-11--13-38-09/0/s JEEP GRAND CHEROKEE V6 2018 ['VW CAN Ign']\n",
"Match found: 900dfa83b4addfe6/2023-12-30--19-20-08/28/s JEEP GRAND CHEROKEE V6 2018 ['VW CAN Ign']\n",
"Match found: 20acda0eb23d7f23/2024-01-19--17-33-26/41/s JEEP GRAND CHEROKEE 2019 ['VW CAN Ign']\n",
"Match found: 1cc3b46843cad2ca/2024-01-10--20-20-54/24/s JEEP GRAND CHEROKEE 2019 ['VW CAN Ign']\n",
"Match found: 2d9b6425552c52c1/2023-12-07--10-31-46/22/s JEEP GRAND CHEROKEE 2019 ['VW CAN Ign']\n",
"Match found: ae679616266f4096/2023-12-04--13-13-56/16/s RAM HD 5TH GEN ['Tesla 3/Y CAN Ign']\n",
"Match found: ae679616266f4096/2024-01-08--07-58-12/65/s RAM HD 5TH GEN ['Tesla 3/Y CAN Ign']\n",
"Match found: ae679616266f4096/2023-12-05--15-43-46/25/s RAM HD 5TH GEN ['Tesla 3/Y CAN Ign']\n",
"Match found: 6dae2984cc53cd7f/2024-01-09--21-41-11/4/s FORD BRONCO SPORT 1ST GEN ['Rivian CAN Ign']\n",
"Match found: 440a155809ba2b6d/2023-12-30--08-51-53/2/s FORD BRONCO SPORT 1ST GEN ['Rivian CAN Ign']\n",
"Match found: 6dae2984cc53cd7f/2024-01-06--10-11-07/1/s FORD BRONCO SPORT 1ST GEN ['Rivian CAN Ign']\n",
"Match found: a4218e6416dfd978/2023-11-27--13-48-46/19/s FORD ESCAPE 4TH GEN ['Rivian CAN Ign']\n",
"Match found: a4218e6416dfd978/2023-11-10--14-13-14/0/s FORD ESCAPE 4TH GEN ['Rivian CAN Ign']\n",
"Match found: a4218e6416dfd978/2023-11-27--13-48-46/4/s FORD ESCAPE 4TH GEN ['Rivian CAN Ign']\n",
"Match found: 8a732841c3a8d5ef/2023-12-10--19-02-33/3/s FORD EXPLORER 6TH GEN ['Rivian CAN Ign']\n",
"Match found: 0b91b433b9332780/2023-12-28--14-02-49/4/s FORD EXPLORER 6TH GEN ['Rivian CAN Ign']\n",
"Match found: 8a732841c3a8d5ef/2023-11-09--07-28-12/1/s FORD EXPLORER 6TH GEN ['Rivian CAN Ign']\n",
"Match found: e886087f430e7fe7/2023-11-05--19-59-40/59/s FORD FOCUS 4TH GEN ['Rivian CAN Ign']\n",
"Match found: e886087f430e7fe7/2023-11-05--19-59-40/82/s FORD FOCUS 4TH GEN ['Rivian CAN Ign']\n",
"Match found: e886087f430e7fe7/2023-11-05--19-59-40/106/s FORD FOCUS 4TH GEN ['Rivian CAN Ign']\n"
]
}
],
"source": [
"from openpilot.tools.lib.logreader import LogReader\n",
"from tqdm.notebook import tqdm, tnrange\n",
"\n",
"# Example search for CAN ignition messages\n",
"# Be careful when filtering by bus, account for odd harness arrangements on Honda/HKG\n",
"\n",
"BUSES_TO_SEARCH = [0, 1, 2]\n",
"\n",
"# Support for external Red Panda\n",
"EXTERNAL_PANDA_BUSES = [bus + 4 for bus in BUSES_TO_SEARCH]\n",
"\n",
"MESSAGES_TO_FIND = {\n",
" 0x1F1: \"GM CAN Ign\",\n",
" 0x152: \"Rivian CAN Ign\",\n",
" 0x221: \"Tesla 3/Y CAN Ign\",\n",
" 0x9E: \"Mazda CAN Ign\",\n",
" 0x3C0: \"VW CAN Ign\",\n",
"}\n",
"\n",
"progress_bar = tnrange(len(TEST_SEGMENTS), desc=\"segments searched\")\n",
"\n",
"for segment in TEST_SEGMENTS:\n",
" lr = LogReader(segment)\n",
" CP = lr.first(\"carParams\")\n",
" if CP is None:\n",
" progress_bar.update()\n",
" continue\n",
"\n",
" can_packets = [msg for msg in lr if msg.which() == \"can\"]\n",
" matched_messages = set()\n",
"\n",
" for packet in can_packets:\n",
" for msg in packet.can:\n",
" if msg.address in MESSAGES_TO_FIND and msg.src in (BUSES_TO_SEARCH + EXTERNAL_PANDA_BUSES):\n",
" # print(msg)\n",
" matched_messages.add(msg.address)\n",
"\n",
" if len(matched_messages) > 0:\n",
" message_names = [MESSAGES_TO_FIND[message] for message in matched_messages]\n",
" print(f\"Match found: {segment:<45} {CP.carFingerprint:<38} {message_names}\")\n",
"\n",
" progress_bar.update()\n"
]
},
{
"cell_type": "code",
"execution_count": null,
"id": "7724dd97-f62e-4fd3-9f64-63d49be669d2",
"metadata": {},
"outputs": [],
"source": []
},
{
"cell_type": "code",
"execution_count": null,
"id": "9f393e00-8efd-40fb-a41e-d312531a83e8",
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3 (ipykernel)",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.12.0"
}
},
"nbformat": 4,
"nbformat_minor": 5
}

@ -13,6 +13,7 @@ from functools import partial
from opendbc.car.fingerprints import MIGRATION
from openpilot.common.basedir import BASEDIR
from openpilot.common.swaglog import cloudlog
from openpilot.tools.cabana.dbc.generate_dbc_json import generate_dbc_dict
from openpilot.tools.lib.logreader import LogReader, ReadMode, save_log
from openpilot.selfdrive.test.process_replay.migration import migrate_all
@ -90,11 +91,10 @@ def juggle_route(route_or_segment_name, can, layout, dbc, should_migrate):
if dbc is None:
try:
CP = lr.first('carParams')
platform = CP.carFingerprint
DBC = __import__(f"opendbc.car.{CP.brand}.values", fromlist=['DBC']).DBC
dbc = DBC[MIGRATION.get(CP.carFingerprint, CP.carFingerprint)]['pt']
platform = MIGRATION.get(CP.carFingerprint, CP.carFingerprint)
dbc = generate_dbc_dict()[platform]
except Exception:
cloudlog.error("Failed to get DBC name from logs!")
cloudlog.exception("Failed to get DBC name from logs!")
with tempfile.NamedTemporaryFile(suffix='.rlog', dir=juggle_dir) as tmp:
save_log(tmp.name, all_data, compress=False)

@ -49,7 +49,7 @@ class SteeringAccuracyTool:
active = sm['controlsState'].active
steer = sm['carOutput'].actuatorsOutput.torque
standstill = sm['carState'].standstill
steer_limited = abs(sm['carControl'].actuators.torque - sm['carControl'].actuatorsOutput.torque) > 1e-2
steer_limited_by_controls = abs(sm['carControl'].actuators.torque - sm['carControl'].actuatorsOutput.torque) > 1e-2
overriding = sm['carState'].steeringPressed
changing_lanes = sm['modelV2'].meta.laneChangeState != 0
model_points = sm['modelV2'].position.y
@ -77,7 +77,7 @@ class SteeringAccuracyTool:
self.speed_group_stats[group][angle_abs]["steer"] += abs(steer)
if len(model_points):
self.speed_group_stats[group][angle_abs]["dpp"] += abs(model_points[0])
if steer_limited:
if steer_limited_by_controls:
self.speed_group_stats[group][angle_abs]["limited"] += 1
if control_state.saturated:
self.speed_group_stats[group][angle_abs]["saturated"] += 1

@ -12,11 +12,11 @@ resolution-markers = [
[[package]]
name = "aiohappyeyeballs"
version = "2.4.6"
version = "2.4.8"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/08/07/508f9ebba367fc3370162e53a3cfd12f5652ad79f0e0bfdf9f9847c6f159/aiohappyeyeballs-2.4.6.tar.gz", hash = "sha256:9b05052f9042985d32ecbe4b59a77ae19c006a78f1344d7fdad69d28ded3d0b0", size = 21726 }
sdist = { url = "https://files.pythonhosted.org/packages/de/7c/79a15272e88d2563c9d63599fa59f05778975f35b255bf8f90c8b12b4ada/aiohappyeyeballs-2.4.8.tar.gz", hash = "sha256:19728772cb12263077982d2f55453babd8bec6a052a926cd5c0c42796da8bf62", size = 22337 }
wheels = [
{ url = "https://files.pythonhosted.org/packages/44/4c/03fb05f56551828ec67ceb3665e5dc51638042d204983a03b0a1541475b6/aiohappyeyeballs-2.4.6-py3-none-any.whl", hash = "sha256:147ec992cf873d74f5062644332c539fcd42956dc69453fe5204195e560517e1", size = 14543 },
{ url = "https://files.pythonhosted.org/packages/52/0e/b187e2bb3eeb2644515109657c4474d65a84e7123de249bf1e8467d04a65/aiohappyeyeballs-2.4.8-py3-none-any.whl", hash = "sha256:6cac4f5dd6e34a9644e69cf9021ef679e4394f54e58a183056d12009e42ea9e3", size = 15005 },
]
[[package]]
@ -760,13 +760,13 @@ wheels = [
[[package]]
name = "libusb1"
version = "3.2.0"
version = "3.3.0"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/d9/b7/9e833af6cb52fa2aece1c6a1378667ca0172bead14f63ffccc3cb9862df3/libusb1-3.2.0.tar.gz", hash = "sha256:a11a6095e718cd49418a96329314da271cca6be7b4317a142724523371ac8961", size = 105601 }
sdist = { url = "https://files.pythonhosted.org/packages/69/c7/3c441fb0628b5afdfe68768f90f8d6ce74dc08e72691fb78d0875db06c48/libusb1-3.3.0.tar.gz", hash = "sha256:b642aa518689f8e053f61955cba274e72bc8d0794c65d7990745aaae90dfc8a1", size = 107253 }
wheels = [
{ url = "https://files.pythonhosted.org/packages/fc/35/d5bde9434fc734709960a94cc489d487184d0ab08e5867311d5a4c64fcea/libusb1-3.2.0-py3-none-any.whl", hash = "sha256:048d4fb79021ec05af667a32e51a911578fc63ab3ed48a4f4fe0f67da797f416", size = 65829 },
{ url = "https://files.pythonhosted.org/packages/a3/cd/ef05b2c67fff2d704aa0325993187ce6a6d04f40ba4be953766b47f5f949/libusb1-3.2.0-py3-none-win32.whl", hash = "sha256:5dc48d6f5207e184cb53278527e7d8e5f4051d8bc419bd15b564c37dc5cca268", size = 127781 },
{ url = "https://files.pythonhosted.org/packages/f9/82/8bcadf2794fa2d39ec100a4f3945db58c316d55c1a0e79ac2cf81c754282/libusb1-3.2.0-py3-none-win_amd64.whl", hash = "sha256:b13acc618263348c91bc4476fadada47be98b7924d6f60e79e3f1da67ac39ddc", size = 139410 },
{ url = "https://files.pythonhosted.org/packages/c7/48/b24b810b14595bd4680030f73a31119120069a8857f41554f00e00b57229/libusb1-3.3.0-py3-none-any.whl", hash = "sha256:7923ff2bbe43878e1c7cf733fde49cca844ecada29dbc436033bca6171cda41f", size = 67044 },
{ url = "https://files.pythonhosted.org/packages/3f/45/52980eedf3fb78711960a558465b3d998beed327fcd2b8483119527adc44/libusb1-3.3.0-py3-none-win32.whl", hash = "sha256:270f35b3a8faddd63d78de9b2341e49f6aed6083dceb4b04f47b95fd944e8d00", size = 128992 },
{ url = "https://files.pythonhosted.org/packages/af/d3/992bfd5bcd9d7a978563d3dabb11d0fce5cf7ceea73d9633fbadba93df4e/libusb1-3.3.0-py3-none-win_amd64.whl", hash = "sha256:61e2b4efdbacdd689bf4eab6b9afa2d6ee8a4bae20ffbf7c5785024d25fa3258", size = 140624 },
]
[[package]]
@ -1578,16 +1578,16 @@ wheels = [
[[package]]
name = "protobuf"
version = "5.29.3"
version = "6.30.0"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/f7/d1/e0a911544ca9993e0f17ce6d3cc0932752356c1b0a834397f28e63479344/protobuf-5.29.3.tar.gz", hash = "sha256:5da0f41edaf117bde316404bad1a486cb4ededf8e4a54891296f648e8e076620", size = 424945 }
sdist = { url = "https://files.pythonhosted.org/packages/53/6a/2629bb3529e5bdfbd6c4608ff5c7d942cd4beae85793f84ba543aab2548a/protobuf-6.30.0.tar.gz", hash = "sha256:852b675d276a7d028f660da075af1841c768618f76b90af771a8e2c29e6f5965", size = 429239 }
wheels = [
{ url = "https://files.pythonhosted.org/packages/dc/7a/1e38f3cafa022f477ca0f57a1f49962f21ad25850c3ca0acd3b9d0091518/protobuf-5.29.3-cp310-abi3-win32.whl", hash = "sha256:3ea51771449e1035f26069c4c7fd51fba990d07bc55ba80701c78f886bf9c888", size = 422708 },
{ url = "https://files.pythonhosted.org/packages/61/fa/aae8e10512b83de633f2646506a6d835b151edf4b30d18d73afd01447253/protobuf-5.29.3-cp310-abi3-win_amd64.whl", hash = "sha256:a4fa6f80816a9a0678429e84973f2f98cbc218cca434abe8db2ad0bffc98503a", size = 434508 },
{ url = "https://files.pythonhosted.org/packages/dd/04/3eaedc2ba17a088961d0e3bd396eac764450f431621b58a04ce898acd126/protobuf-5.29.3-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:a8434404bbf139aa9e1300dbf989667a83d42ddda9153d8ab76e0d5dcaca484e", size = 417825 },
{ url = "https://files.pythonhosted.org/packages/4f/06/7c467744d23c3979ce250397e26d8ad8eeb2bea7b18ca12ad58313c1b8d5/protobuf-5.29.3-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:daaf63f70f25e8689c072cfad4334ca0ac1d1e05a92fc15c54eb9cf23c3efd84", size = 319573 },
{ url = "https://files.pythonhosted.org/packages/a8/45/2ebbde52ad2be18d3675b6bee50e68cd73c9e0654de77d595540b5129df8/protobuf-5.29.3-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:c027e08a08be10b67c06bf2370b99c811c466398c357e615ca88c91c07f0910f", size = 319672 },
{ url = "https://files.pythonhosted.org/packages/fd/b2/ab07b09e0f6d143dfb839693aa05765257bceaa13d03bf1a696b78323e7a/protobuf-5.29.3-py3-none-any.whl", hash = "sha256:0a18ed4a24198528f2333802eb075e59dea9d679ab7a6c5efb017a59004d849f", size = 172550 },
{ url = "https://files.pythonhosted.org/packages/aa/76/8b1cbf762d98b09fcb29bbc6eca97dc6e1cd865b97a49c443aa23f1a9f82/protobuf-6.30.0-cp310-abi3-win32.whl", hash = "sha256:7337d76d8efe65ee09ee566b47b5914c517190196f414e5418fa236dfd1aed3e", size = 419141 },
{ url = "https://files.pythonhosted.org/packages/57/50/2ea2fb4533321438f5106723c70c303529ba184540e619ebe75e790d402e/protobuf-6.30.0-cp310-abi3-win_amd64.whl", hash = "sha256:9b33d51cc95a7ec4f407004c8b744330b6911a37a782e2629c67e1e8ac41318f", size = 430995 },
{ url = "https://files.pythonhosted.org/packages/a1/7d/a7dfa7aa3deda114920b1ed57c0026e85a976e74658db2784a0443510252/protobuf-6.30.0-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:52d4bb6fe76005860e1d0b8bfa126f5c97c19cc82704961f60718f50be16942d", size = 417570 },
{ url = "https://files.pythonhosted.org/packages/11/87/a9c7b020c4072dc34e3a2a3cde69366ffc623afff0e7f10f4e5275aaec01/protobuf-6.30.0-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:7940ab4dfd60d514b2e1d3161549ea7aed5be37d53bafde16001ac470a3e202b", size = 317310 },
{ url = "https://files.pythonhosted.org/packages/95/66/424db2262723781dc94208ff9ce201df2f44f18a46fbff3c067812c6b5b9/protobuf-6.30.0-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:d79bf6a202a536b192b7e8d295d7eece0c86fbd9b583d147faf8cfeff46bf598", size = 316203 },
{ url = "https://files.pythonhosted.org/packages/51/6f/21c2b7de96c3051f847a4a88a12fdf015ed6b7d50fc131fb101a739bd7a5/protobuf-6.30.0-py3-none-any.whl", hash = "sha256:e5ef216ea061b262b8994cb6b7d6637a4fb27b3fb4d8e216a6040c0b93bd10d7", size = 167054 },
]
[[package]]
@ -4279,7 +4279,7 @@ wheels = [
[[package]]
name = "pytest"
version = "8.3.4"
version = "8.3.5"
source = { registry = "https://pypi.org/simple" }
dependencies = [
{ name = "colorama", marker = "sys_platform == 'win32'" },
@ -4287,9 +4287,9 @@ dependencies = [
{ name = "packaging" },
{ name = "pluggy" },
]
sdist = { url = "https://files.pythonhosted.org/packages/05/35/30e0d83068951d90a01852cb1cef56e5d8a09d20c7f511634cc2f7e0372a/pytest-8.3.4.tar.gz", hash = "sha256:965370d062bce11e73868e0335abac31b4d3de0e82f4007408d242b4f8610761", size = 1445919 }
sdist = { url = "https://files.pythonhosted.org/packages/ae/3c/c9d525a414d506893f0cd8a8d0de7706446213181570cdbd766691164e40/pytest-8.3.5.tar.gz", hash = "sha256:f4efe70cc14e511565ac476b57c279e12a855b11f48f212af1080ef2263d3845", size = 1450891 }
wheels = [
{ url = "https://files.pythonhosted.org/packages/11/92/76a1c94d3afee238333bc0a42b82935dd8f9cf8ce9e336ff87ee14d9e1cf/pytest-8.3.4-py3-none-any.whl", hash = "sha256:50e16d954148559c9a74109af1eaf0c945ba2d8f30f0a3d3335edde19788b6f6", size = 343083 },
{ url = "https://files.pythonhosted.org/packages/30/3d/64ad57c803f1fa1e963a7946b6e0fea4a70df53c1a7fed304586539c2bac/pytest-8.3.5-py3-none-any.whl", hash = "sha256:c69214aa47deac29fad6c2a4f590b9c4a9fdb16a403176fe154b79c0b4d4d820", size = 343634 },
]
[[package]]
@ -4703,11 +4703,11 @@ wheels = [
[[package]]
name = "scons"
version = "4.8.1"
version = "4.9.0"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/b9/76/a2c1293642f9a448f2d012cabf525be69ca5abf4af289bc0935ac1554ee8/scons-4.8.1.tar.gz", hash = "sha256:5b641357904d2f56f7bfdbb37e165ab996b6143c948b9df0efc7305f54949daa", size = 3244174 }
sdist = { url = "https://files.pythonhosted.org/packages/61/7e/79e07dc2eb8874580934cd0c834a8a78f15d5b0d6155a424f6c7b35441c3/scons-4.9.0.tar.gz", hash = "sha256:f1a5e161bf3d1411d780d65d7919654b9405555994621d3d68e42d62114b592a", size = 3251763 }
wheels = [
{ url = "https://files.pythonhosted.org/packages/b8/a7/823091100c88d7d992c8c608d82a88ed59e227d13f8ccb33ea7a96d43d51/SCons-4.8.1-py3-none-any.whl", hash = "sha256:a4c3b434330e2d7d975002fd6783284ba348bf394db94c8f83fdc5bf69cdb8d7", size = 4123564 },
{ url = "https://files.pythonhosted.org/packages/18/f5/77635f6c68ed742a23e1f52977267e191ea7c2aec89b9604a86487405da1/scons-4.9.0-py3-none-any.whl", hash = "sha256:c8cc309db0f91cffdc27c1374fa3d31e9421bcb31d210de071b0b11adc84739b", size = 4130637 },
]
[[package]]

Loading…
Cancel
Save