Merge branch 'master' into gwm-driving

gwm-driving
YassineYousfi 2 weeks ago committed by GitHub
commit 1bd650a423
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
  1. 3
      .gitattributes
  2. 2
      .github/workflows/selfdrive_tests.yaml
  3. 4
      Dockerfile.openpilot
  4. 6
      Jenkinsfile
  5. 4
      RELEASES.md
  6. 10
      cereal/log.capnp
  7. 11
      common/filter_simple.py
  8. 2
      common/params_keys.h
  9. 13
      common/pid.py
  10. 2
      launch_env.sh
  11. 2
      opendbc_repo
  12. 2
      panda
  13. 10
      pyproject.toml
  14. 3
      selfdrive/SConscript
  15. 3
      selfdrive/assets/fonts/NotoColorEmoji-Regular.ttf
  16. 3
      selfdrive/assets/fonts/NotoColorEmoji.ttf
  17. 6
      selfdrive/car/tests/test_car_interfaces.py
  18. 2
      selfdrive/car/tests/test_models.py
  19. 14
      selfdrive/controls/controlsd.py
  20. 2
      selfdrive/controls/lib/drive_helpers.py
  21. 20
      selfdrive/controls/lib/latcontrol.py
  22. 6
      selfdrive/controls/lib/latcontrol_angle.py
  23. 11
      selfdrive/controls/lib/latcontrol_pid.py
  24. 63
      selfdrive/controls/lib/latcontrol_torque.py
  25. 2
      selfdrive/controls/lib/longcontrol.py
  26. 9
      selfdrive/controls/tests/test_latcontrol.py
  27. 12
      selfdrive/modeld/dmonitoringmodeld.py
  28. 3
      selfdrive/modeld/models/README.md
  29. 2
      selfdrive/modeld/models/dmonitoring_model.current
  30. 4
      selfdrive/modeld/models/dmonitoring_model.onnx
  31. 10
      selfdrive/monitoring/helpers.py
  32. 1
      selfdrive/monitoring/test_monitoring.py
  33. 2
      selfdrive/test/process_replay/ref_commit
  34. 2
      selfdrive/test/setup_device_ci.sh
  35. 11
      selfdrive/test/test_onroad.py
  36. 2
      selfdrive/ui/.gitignore
  37. 2
      selfdrive/ui/SConscript
  38. 34
      selfdrive/ui/installer/installer.cc
  39. 82
      selfdrive/ui/layouts/home.py
  40. 19
      selfdrive/ui/layouts/main.py
  41. 214
      selfdrive/ui/layouts/onboarding.py
  42. 176
      selfdrive/ui/layouts/settings/developer.py
  43. 168
      selfdrive/ui/layouts/settings/device.py
  44. 98
      selfdrive/ui/layouts/settings/firehose.py
  45. 13
      selfdrive/ui/layouts/settings/settings.py
  46. 158
      selfdrive/ui/layouts/settings/software.py
  47. 248
      selfdrive/ui/layouts/settings/toggles.py
  48. 69
      selfdrive/ui/layouts/sidebar.py
  49. 75
      selfdrive/ui/onroad/alert_renderer.py
  50. 47
      selfdrive/ui/onroad/augmented_road_view.py
  51. 15
      selfdrive/ui/onroad/cameraview.py
  52. 14
      selfdrive/ui/onroad/driver_camera_dialog.py
  53. 16
      selfdrive/ui/onroad/driver_state.py
  54. 7
      selfdrive/ui/onroad/exp_button.py
  55. 11
      selfdrive/ui/onroad/hud_renderer.py
  56. 62
      selfdrive/ui/onroad/model_renderer.py
  57. 4
      selfdrive/ui/tests/create_test_translations.sh
  58. 5
      selfdrive/ui/tests/cycle_offroad_alerts.py
  59. 2
      selfdrive/ui/tests/test_raylib_ui.py
  60. 2
      selfdrive/ui/tests/test_runner.cc
  61. 2
      selfdrive/ui/tests/test_translations.py
  62. 36
      selfdrive/ui/tests/test_ui/print_mouse_coords.py
  63. 217
      selfdrive/ui/tests/test_ui/raylib_screenshots.py
  64. 0
      selfdrive/ui/translations/ar.ts
  65. 2
      selfdrive/ui/translations/auto_translate.py
  66. 0
      selfdrive/ui/translations/de.ts
  67. 0
      selfdrive/ui/translations/en.ts
  68. 0
      selfdrive/ui/translations/es.ts
  69. 0
      selfdrive/ui/translations/fr.ts
  70. 0
      selfdrive/ui/translations/ja.ts
  71. 0
      selfdrive/ui/translations/ko.ts
  72. 24
      selfdrive/ui/translations/languages.json
  73. 0
      selfdrive/ui/translations/nl.ts
  74. 0
      selfdrive/ui/translations/pl.ts
  75. 0
      selfdrive/ui/translations/pt-BR.ts
  76. 0
      selfdrive/ui/translations/th.ts
  77. 0
      selfdrive/ui/translations/tr.ts
  78. 0
      selfdrive/ui/translations/zh-CHS.ts
  79. 0
      selfdrive/ui/translations/zh-CHT.ts
  80. 6
      selfdrive/ui/ui.py
  81. 53
      selfdrive/ui/ui_state.py
  82. 6
      selfdrive/ui/update_translations.py
  83. 20
      selfdrive/ui/widgets/exp_mode_button.py
  84. 225
      selfdrive/ui/widgets/offroad_alerts.py
  85. 55
      selfdrive/ui/widgets/pairing_dialog.py
  86. 19
      selfdrive/ui/widgets/prime.py
  87. 36
      selfdrive/ui/widgets/setup.py
  88. 57
      selfdrive/ui/widgets/ssh_key.py
  89. 2
      system/camerad/cameras/camera_qcom2.cc
  90. 2
      system/hardware/fan_controller.py
  91. 58
      system/hardware/tici/agnos.json
  92. 82
      system/hardware/tici/all-partitions.json
  93. 20
      system/hardware/tici/updater
  94. 3
      system/hardware/tici/updater_magic
  95. 3
      system/hardware/tici/updater_weston
  96. 4
      system/loggerd/loggerd.h
  97. 2
      system/loggerd/uploader.py
  98. 2
      system/manager/build.py
  99. 4
      system/manager/process_config.py
  100. 97
      system/ui/lib/application.py
  101. Some files were not shown because too many files have changed in this diff Show More

3
.gitattributes vendored

@ -10,7 +10,8 @@
*.wav filter=lfs diff=lfs merge=lfs -text *.wav filter=lfs diff=lfs merge=lfs -text
selfdrive/car/tests/test_models_segs.txt filter=lfs diff=lfs merge=lfs -text selfdrive/car/tests/test_models_segs.txt filter=lfs diff=lfs merge=lfs -text
system/hardware/tici/updater filter=lfs diff=lfs merge=lfs -text system/hardware/tici/updater_weston filter=lfs diff=lfs merge=lfs -text
system/hardware/tici/updater_magic filter=lfs diff=lfs merge=lfs -text
third_party/**/*.a filter=lfs diff=lfs merge=lfs -text third_party/**/*.a filter=lfs diff=lfs merge=lfs -text
third_party/**/*.so filter=lfs diff=lfs merge=lfs -text third_party/**/*.so filter=lfs diff=lfs merge=lfs -text
third_party/**/*.so.* filter=lfs diff=lfs merge=lfs -text third_party/**/*.so.* filter=lfs diff=lfs merge=lfs -text

@ -225,7 +225,7 @@ jobs:
(github.event.pull_request.head.repo.full_name == 'commaai/openpilot')) (github.event.pull_request.head.repo.full_name == 'commaai/openpilot'))
&& fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]')
|| fromJSON('["ubuntu-24.04"]') }} || fromJSON('["ubuntu-24.04"]') }}
if: (github.repository == 'commaai/openpilot') && ((github.event_name != 'pull_request') || (github.event.pull_request.head.repo.full_name == 'commaai/openpilot')) if: false # FIXME: Started to timeout recently
steps: steps:
- uses: actions/checkout@v4 - uses: actions/checkout@v4
with: with:

@ -9,4 +9,6 @@ WORKDIR ${OPENPILOT_PATH}
COPY . ${OPENPILOT_PATH}/ COPY . ${OPENPILOT_PATH}/
RUN scons --cache-readonly -j$(nproc) ENV UV_BIN="/home/batman/.local/bin/"
ENV PATH="$UV_BIN:$PATH"
RUN UV_PROJECT_ENVIRONMENT=$VIRTUAL_ENV uv run scons --cache-readonly -j$(nproc)

6
Jenkinsfile vendored

@ -167,7 +167,7 @@ node {
env.GIT_COMMIT = checkout(scm).GIT_COMMIT env.GIT_COMMIT = checkout(scm).GIT_COMMIT
def excludeBranches = ['__nightly', 'devel', 'devel-staging', 'release3', 'release3-staging', def excludeBranches = ['__nightly', 'devel', 'devel-staging', 'release3', 'release3-staging',
'release-tici', 'release-tizi', 'testing-closet*', 'hotfix-*'] 'release-tici', 'release-tizi', 'release-tizi-staging', 'testing-closet*', 'hotfix-*']
def excludeRegex = excludeBranches.join('|').replaceAll('\\*', '.*') def excludeRegex = excludeBranches.join('|').replaceAll('\\*', '.*')
if (env.BRANCH_NAME != 'master' && !env.BRANCH_NAME.contains('__jenkins_loop_')) { if (env.BRANCH_NAME != 'master' && !env.BRANCH_NAME.contains('__jenkins_loop_')) {
@ -178,8 +178,8 @@ node {
try { try {
if (env.BRANCH_NAME == 'devel-staging') { if (env.BRANCH_NAME == 'devel-staging') {
deviceStage("build release3-staging", "tizi-needs-can", [], [ deviceStage("build release-tizi-staging", "tizi-needs-can", [], [
step("build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"), step("build release-tizi-staging", "RELEASE_BRANCH=release-tizi-staging $SOURCE_DIR/release/build_release.sh"),
]) ])
} }

@ -1,10 +1,12 @@
Version 0.10.1 (2025-09-08) Version 0.10.1 (2025-09-08)
======================== ========================
* New driving model #36087 * New driving model #36114
* World Model: removed global localization inputs * World Model: removed global localization inputs
* World Model: 2x the number of parameters * World Model: 2x the number of parameters
* World Model: trained on 4x the number of segments * World Model: trained on 4x the number of segments
* VAE Compression Model: new architecture and training objective
* Driving Vision Model: trained on 4x the number of segments * Driving Vision Model: trained on 4x the number of segments
* New Driver Monitoring model #36198
* Acura TLX 2021 support thanks to MVL! * Acura TLX 2021 support thanks to MVL!
* Honda City 2023 support thanks to vanillagorillaa and drFritz! * Honda City 2023 support thanks to vanillagorillaa and drFritz!
* Honda N-Box 2018 support thanks to miettal! * Honda N-Box 2018 support thanks to miettal!

@ -2146,13 +2146,10 @@ struct Joystick {
struct DriverStateV2 { struct DriverStateV2 {
frameId @0 :UInt32; frameId @0 :UInt32;
modelExecutionTime @1 :Float32; modelExecutionTime @1 :Float32;
dspExecutionTimeDEPRECATED @2 :Float32;
gpuExecutionTime @8 :Float32; gpuExecutionTime @8 :Float32;
rawPredictions @3 :Data; rawPredictions @3 :Data;
poorVisionProb @4 :Float32;
wheelOnRightProb @5 :Float32; wheelOnRightProb @5 :Float32;
leftDriverData @6 :DriverData; leftDriverData @6 :DriverData;
rightDriverData @7 :DriverData; rightDriverData @7 :DriverData;
@ -2167,10 +2164,13 @@ struct DriverStateV2 {
leftBlinkProb @7 :Float32; leftBlinkProb @7 :Float32;
rightBlinkProb @8 :Float32; rightBlinkProb @8 :Float32;
sunglassesProb @9 :Float32; sunglassesProb @9 :Float32;
occludedProb @10 :Float32;
readyProb @11 :List(Float32);
notReadyProb @12 :List(Float32); notReadyProb @12 :List(Float32);
occludedProbDEPRECATED @10 :Float32;
readyProbDEPRECATED @11 :List(Float32);
} }
dspExecutionTimeDEPRECATED @2 :Float32;
poorVisionProbDEPRECATED @4 :Float32;
} }
struct DriverStateDEPRECATED @0xb83c6cc593ed0a00 { struct DriverStateDEPRECATED @0xb83c6cc593ed0a00 {

@ -1,21 +1,16 @@
class FirstOrderFilter: class FirstOrderFilter:
def __init__(self, x0, rc, dt, initialized=True): def __init__(self, x0, rc, dt, initialized=True):
self.x = x0 self.x = x0
self._dt = dt self.dt = dt
self.update_alpha(rc) self.update_alpha(rc)
self.initialized = initialized self.initialized = initialized
def update_dt(self, dt):
self._dt = dt
self.update_alpha(self._rc)
def update_alpha(self, rc): def update_alpha(self, rc):
self._rc = rc self.alpha = self.dt / (rc + self.dt)
self._alpha = self._dt / (self._rc + self._dt)
def update(self, x): def update(self, x):
if self.initialized: if self.initialized:
self.x = (1. - self._alpha) * self.x + self._alpha * x self.x = (1. - self.alpha) * self.x + self.alpha * x
else: else:
self.initialized = True self.initialized = True
self.x = x self.x = x

@ -66,7 +66,7 @@ inline static std::unordered_map<std::string, ParamKeyAttributes> keys = {
{"IsTakingSnapshot", {CLEAR_ON_MANAGER_START, BOOL}}, {"IsTakingSnapshot", {CLEAR_ON_MANAGER_START, BOOL}},
{"IsTestedBranch", {CLEAR_ON_MANAGER_START, BOOL}}, {"IsTestedBranch", {CLEAR_ON_MANAGER_START, BOOL}},
{"JoystickDebugMode", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}}, {"JoystickDebugMode", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}},
{"LanguageSetting", {PERSISTENT, STRING, "main_en"}}, {"LanguageSetting", {PERSISTENT, STRING, "en"}},
{"LastAthenaPingTime", {CLEAR_ON_MANAGER_START, INT}}, {"LastAthenaPingTime", {CLEAR_ON_MANAGER_START, INT}},
{"LastGPSPosition", {PERSISTENT, STRING}}, {"LastGPSPosition", {PERSISTENT, STRING}},
{"LastManagerExitReason", {CLEAR_ON_MANAGER_START, STRING}}, {"LastManagerExitReason", {CLEAR_ON_MANAGER_START, STRING}},

@ -2,11 +2,10 @@ import numpy as np
from numbers import Number from numbers import Number
class PIDController: class PIDController:
def __init__(self, k_p, k_i, k_f=0., k_d=0., pos_limit=1e308, neg_limit=-1e308, rate=100): def __init__(self, k_p, k_i, k_d=0., pos_limit=1e308, neg_limit=-1e308, rate=100):
self._k_p = k_p self._k_p = k_p
self._k_i = k_i self._k_i = k_i
self._k_d = k_d self._k_d = k_d
self.k_f = k_f # feedforward gain
if isinstance(self._k_p, Number): if isinstance(self._k_p, Number):
self._k_p = [[0], [self._k_p]] self._k_p = [[0], [self._k_p]]
if isinstance(self._k_i, Number): if isinstance(self._k_i, Number):
@ -16,7 +15,7 @@ class PIDController:
self.set_limits(pos_limit, neg_limit) self.set_limits(pos_limit, neg_limit)
self.i_rate = 1.0 / rate self.i_dt = 1.0 / rate
self.speed = 0.0 self.speed = 0.0
self.reset() self.reset()
@ -46,12 +45,12 @@ class PIDController:
def update(self, error, error_rate=0.0, speed=0.0, feedforward=0., freeze_integrator=False): def update(self, error, error_rate=0.0, speed=0.0, feedforward=0., freeze_integrator=False):
self.speed = speed self.speed = speed
self.p = float(error) * self.k_p self.p = self.k_p * float(error)
self.f = feedforward * self.k_f self.d = self.k_d * error_rate
self.d = error_rate * self.k_d self.f = feedforward
if not freeze_integrator: if not freeze_integrator:
i = self.i + error * self.k_i * self.i_rate i = self.i + self.k_i * self.i_dt * error
# Don't allow windup if already clipping # Don't allow windup if already clipping
test_control = self.p + i + self.d + self.f test_control = self.p + i + self.d + self.f

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

@ -1 +1 @@
Subproject commit 2eec1af104972b7784644bf38c4c5afb52fc070a Subproject commit b59f8bdcca8d375b4a5a652d2f2d2ec9cd3503d3

@ -1 +1 @@
Subproject commit 1289337ceb6205ad985a5469baa950b319329327 Subproject commit 615009cf0f8fb8f3feadac160fbb0a07e4de171b

@ -72,7 +72,9 @@ dependencies = [
"zstandard", "zstandard",
# ui # ui
"raylib < 5.5.0.3", # TODO: unpin when they fix https://github.com/electronstudio/raylib-python-cffi/issues/186
"qrcode", "qrcode",
"mapbox-earcut",
] ]
[project.optional-dependencies] [project.optional-dependencies]
@ -119,7 +121,6 @@ dev = [
"tabulate", "tabulate",
"types-requests", "types-requests",
"types-tabulate", "types-tabulate",
"raylib < 5.5.0.3", # TODO: unpin when they fix https://github.com/electronstudio/raylib-python-cffi/issues/186
] ]
tools = [ tools = [
@ -262,8 +263,13 @@ lint.flake8-implicit-str-concat.allow-multiline = false
"tools".msg = "Use openpilot.tools" "tools".msg = "Use openpilot.tools"
"pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" "pytest.main".msg = "pytest.main requires special handling that is easy to mess up!"
"unittest".msg = "Use pytest" "unittest".msg = "Use pytest"
"pyray.measure_text_ex".msg = "Use openpilot.system.ui.lib.text_measure"
"time.time".msg = "Use time.monotonic" "time.time".msg = "Use time.monotonic"
# raylib banned APIs
"pyray.measure_text_ex".msg = "Use openpilot.system.ui.lib.text_measure"
"pyray.is_mouse_button_pressed".msg = "This can miss events. Use Widget._handle_mouse_press"
"pyray.is_mouse_button_released".msg = "This can miss events. Use Widget._handle_mouse_release"
"pyray.draw_text".msg = "Use a function (such as rl.draw_font_ex) that takes font as an argument"
[tool.ruff.format] [tool.ruff.format]
quote-style = "preserve" quote-style = "preserve"

@ -3,4 +3,5 @@ SConscript(['controls/lib/lateral_mpc_lib/SConscript'])
SConscript(['controls/lib/longitudinal_mpc_lib/SConscript']) SConscript(['controls/lib/longitudinal_mpc_lib/SConscript'])
SConscript(['locationd/SConscript']) SConscript(['locationd/SConscript'])
SConscript(['modeld/SConscript']) SConscript(['modeld/SConscript'])
SConscript(['ui/SConscript']) if GetOption('extras'):
SConscript(['ui/SConscript'])

@ -1,3 +0,0 @@
version https://git-lfs.github.com/spec/v1
oid sha256:69f216a4ec672bb910d652678301ffe3094c44e5d03276e794ef793d936a1f1d
size 25096376

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:93cdc4ee9aa40e2afceecc63da0ca05ec7aab4bec991ece51a6b52389f48a477
size 10788068

@ -54,8 +54,8 @@ class TestCarInterfaces:
# hypothesis also slows down significantly with just one more message draw # hypothesis also slows down significantly with just one more message draw
LongControl(car_params) LongControl(car_params)
if car_params.steerControlType == CarParams.SteerControlType.angle: if car_params.steerControlType == CarParams.SteerControlType.angle:
LatControlAngle(car_params, car_interface) LatControlAngle(car_params, car_interface, DT_CTRL)
elif car_params.lateralTuning.which() == 'pid': elif car_params.lateralTuning.which() == 'pid':
LatControlPID(car_params, car_interface) LatControlPID(car_params, car_interface, DT_CTRL)
elif car_params.lateralTuning.which() == 'torque': elif car_params.lateralTuning.which() == 'torque':
LatControlTorque(car_params, car_interface) LatControlTorque(car_params, car_interface, DT_CTRL)

@ -183,7 +183,7 @@ class TestCarModelBase(unittest.TestCase):
if tuning == 'pid': if tuning == 'pid':
self.assertTrue(len(self.CP.lateralTuning.pid.kpV)) self.assertTrue(len(self.CP.lateralTuning.pid.kpV))
elif tuning == 'torque': elif tuning == 'torque':
self.assertTrue(self.CP.lateralTuning.torque.kf > 0) self.assertTrue(self.CP.lateralTuning.torque.latAccelFactor > 0)
else: else:
raise Exception("unknown tuning") raise Exception("unknown tuning")

@ -6,7 +6,7 @@ from cereal import car, log
import cereal.messaging as messaging import cereal.messaging as messaging
from openpilot.common.constants import CV from openpilot.common.constants import CV
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper from openpilot.common.realtime import config_realtime_process, DT_CTRL, Priority, Ratekeeper
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from opendbc.car.car_helpers import interfaces from opendbc.car.car_helpers import interfaces
@ -17,6 +17,7 @@ from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID
from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle, STEER_ANGLE_SATURATION_THRESHOLD from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle, STEER_ANGLE_SATURATION_THRESHOLD
from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque
from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.longcontrol import LongControl
from openpilot.selfdrive.modeld.modeld import LAT_SMOOTH_SECONDS
from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose
State = log.SelfdriveState.OpenpilotState State = log.SelfdriveState.OpenpilotState
@ -35,7 +36,7 @@ class Controls:
self.CI = interfaces[self.CP.carFingerprint](self.CP) self.CI = interfaces[self.CP.carFingerprint](self.CP)
self.sm = messaging.SubMaster(['liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState', self.sm = messaging.SubMaster(['liveDelay', 'liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState',
'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput', 'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput',
'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState') 'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState')
self.pm = messaging.PubMaster(['carControl', 'controlsState']) self.pm = messaging.PubMaster(['carControl', 'controlsState'])
@ -51,11 +52,11 @@ class Controls:
self.VM = VehicleModel(self.CP) self.VM = VehicleModel(self.CP)
self.LaC: LatControl self.LaC: LatControl
if self.CP.steerControlType == car.CarParams.SteerControlType.angle: if self.CP.steerControlType == car.CarParams.SteerControlType.angle:
self.LaC = LatControlAngle(self.CP, self.CI) self.LaC = LatControlAngle(self.CP, self.CI, DT_CTRL)
elif self.CP.lateralTuning.which() == 'pid': elif self.CP.lateralTuning.which() == 'pid':
self.LaC = LatControlPID(self.CP, self.CI) self.LaC = LatControlPID(self.CP, self.CI, DT_CTRL)
elif self.CP.lateralTuning.which() == 'torque': elif self.CP.lateralTuning.which() == 'torque':
self.LaC = LatControlTorque(self.CP, self.CI) self.LaC = LatControlTorque(self.CP, self.CI, DT_CTRL)
def update(self): def update(self):
self.sm.update(15) self.sm.update(15)
@ -117,11 +118,12 @@ class Controls:
# Reset desired curvature to current to avoid violating the limits on engage # Reset desired curvature to current to avoid violating the limits on engage
new_desired_curvature = model_v2.action.desiredCurvature if CC.latActive else self.curvature new_desired_curvature = model_v2.action.desiredCurvature if CC.latActive else self.curvature
self.desired_curvature, curvature_limited = clip_curvature(CS.vEgo, self.desired_curvature, new_desired_curvature, lp.roll) self.desired_curvature, curvature_limited = clip_curvature(CS.vEgo, self.desired_curvature, new_desired_curvature, lp.roll)
lat_delay = self.sm["liveDelay"].lateralDelay + LAT_SMOOTH_SECONDS
actuators.curvature = self.desired_curvature actuators.curvature = self.desired_curvature
steer, steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, steer, steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp,
self.steer_limited_by_safety, self.desired_curvature, self.steer_limited_by_safety, self.desired_curvature,
curvature_limited) # TODO what if not available curvature_limited, lat_delay)
actuators.torque = float(steer) actuators.torque = float(steer)
actuators.steeringAngleDeg = float(steeringAngleDeg) actuators.steeringAngleDeg = float(steeringAngleDeg)
# Ensure no NaNs/Infs # Ensure no NaNs/Infs

@ -22,7 +22,7 @@ def smooth_value(val, prev_val, tau, dt=DT_MDL):
alpha = 1 - np.exp(-dt/tau) if tau > 0 else 1 alpha = 1 - np.exp(-dt/tau) if tau > 0 else 1
return alpha * val + (1 - alpha) * prev_val return alpha * val + (1 - alpha) * prev_val
def clip_curvature(v_ego, prev_curvature, new_curvature, roll): def clip_curvature(v_ego, prev_curvature, new_curvature, roll) -> tuple[float, bool]:
# This function respects ISO lateral jerk and acceleration limits + a max curvature # This function respects ISO lateral jerk and acceleration limits + a max curvature
v_ego = max(v_ego, MIN_SPEED) 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 max_curvature_rate = MAX_LATERAL_JERK / (v_ego ** 2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755

@ -1,31 +1,29 @@
import numpy as np import numpy as np
from abc import abstractmethod, ABC from abc import abstractmethod, ABC
from openpilot.common.realtime import DT_CTRL
class LatControl(ABC): class LatControl(ABC):
def __init__(self, CP, CI): def __init__(self, CP, CI, dt):
self.sat_count_rate = 1.0 * DT_CTRL self.dt = dt
self.sat_limit = CP.steerLimitTimer self.sat_limit = CP.steerLimitTimer
self.sat_count = 0. self.sat_time = 0.
self.sat_check_min_speed = 10. self.sat_check_min_speed = 10.
# we define the steer torque scale as [-1.0...1.0] # we define the steer torque scale as [-1.0...1.0]
self.steer_max = 1.0 self.steer_max = 1.0
@abstractmethod @abstractmethod
def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, calibrated_pose, curvature_limited): def update(self, active: bool, CS, VM, params, steer_limited_by_safety: bool, desired_curvature: float, curvature_limited: bool, lat_delay: float):
pass pass
def reset(self): def reset(self):
self.sat_count = 0. self.sat_time = 0.
def _check_saturation(self, saturated, CS, steer_limited_by_safety, curvature_limited): def _check_saturation(self, saturated, CS, steer_limited_by_safety, curvature_limited):
# Saturated only if control output is not being limited by car torque/angle rate limits # 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_safety and not CS.steeringPressed: if (saturated or curvature_limited) and CS.vEgo > self.sat_check_min_speed and not steer_limited_by_safety and not CS.steeringPressed:
self.sat_count += self.sat_count_rate self.sat_time += self.dt
else: else:
self.sat_count -= self.sat_count_rate self.sat_time -= self.dt
self.sat_count = np.clip(self.sat_count, 0.0, self.sat_limit) self.sat_time = np.clip(self.sat_time, 0.0, self.sat_limit)
return self.sat_count > (self.sat_limit - 1e-3) return self.sat_time > (self.sat_limit - 1e-3)

@ -8,12 +8,12 @@ STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees
class LatControlAngle(LatControl): class LatControlAngle(LatControl):
def __init__(self, CP, CI): def __init__(self, CP, CI, dt):
super().__init__(CP, CI) super().__init__(CP, CI, dt)
self.sat_check_min_speed = 5. self.sat_check_min_speed = 5.
self.use_steer_limited_by_safety = CP.brand == "tesla" self.use_steer_limited_by_safety = CP.brand == "tesla"
def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited): def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited, lat_delay):
angle_log = log.ControlsState.LateralAngleState.new_message() angle_log = log.ControlsState.LateralAngleState.new_message()
if not active: if not active:

@ -6,14 +6,15 @@ from openpilot.common.pid import PIDController
class LatControlPID(LatControl): class LatControlPID(LatControl):
def __init__(self, CP, CI): def __init__(self, CP, CI, dt):
super().__init__(CP, CI) super().__init__(CP, CI, dt)
self.pid = PIDController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV), self.pid = PIDController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV),
(CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV), (CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV),
k_f=CP.lateralTuning.pid.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max) pos_limit=self.steer_max, neg_limit=-self.steer_max)
self.ff_factor = CP.lateralTuning.pid.kf
self.get_steer_feedforward = CI.get_steer_feedforward_function() self.get_steer_feedforward = CI.get_steer_feedforward_function()
def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited): def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited, lat_delay):
pid_log = log.ControlsState.LateralPIDState.new_message() pid_log = log.ControlsState.LateralPIDState.new_message()
pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringAngleDeg = float(CS.steeringAngleDeg)
pid_log.steeringRateDeg = float(CS.steeringRateDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg)
@ -30,7 +31,7 @@ class LatControlPID(LatControl):
else: else:
# offset does not contribute to resistive torque # offset does not contribute to resistive torque
ff = self.get_steer_feedforward(angle_steers_des_no_offset, CS.vEgo) ff = self.ff_factor * self.get_steer_feedforward(angle_steers_des_no_offset, CS.vEgo)
freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5
output_torque = self.pid.update(error, output_torque = self.pid.update(error,

@ -1,9 +1,13 @@
import math import math
import numpy as np import numpy as np
from collections import deque
from cereal import log from cereal import log
from opendbc.car.lateral import FRICTION_THRESHOLD, get_friction from opendbc.car.lateral import FRICTION_THRESHOLD, get_friction
from opendbc.car.tests.test_lateral_limits import MAX_LAT_JERK_UP
from openpilot.common.constants import ACCELERATION_DUE_TO_GRAVITY from openpilot.common.constants import ACCELERATION_DUE_TO_GRAVITY
from openpilot.common.filter_simple import FirstOrderFilter
from openpilot.selfdrive.controls.lib.drive_helpers import MIN_SPEED
from openpilot.selfdrive.controls.lib.latcontrol import LatControl from openpilot.selfdrive.controls.lib.latcontrol import LatControl
from openpilot.common.pid import PIDController from openpilot.common.pid import PIDController
@ -20,18 +24,24 @@ from openpilot.common.pid import PIDController
LOW_SPEED_X = [0, 10, 20, 30] LOW_SPEED_X = [0, 10, 20, 30]
LOW_SPEED_Y = [15, 13, 10, 5] LOW_SPEED_Y = [15, 13, 10, 5]
KP = 1.0
KI = 0.3
KD = 0.0
class LatControlTorque(LatControl): class LatControlTorque(LatControl):
def __init__(self, CP, CI): def __init__(self, CP, CI, dt):
super().__init__(CP, CI) super().__init__(CP, CI, dt)
self.torque_params = CP.lateralTuning.torque.as_builder() self.torque_params = CP.lateralTuning.torque.as_builder()
self.torque_from_lateral_accel = CI.torque_from_lateral_accel() self.torque_from_lateral_accel = CI.torque_from_lateral_accel()
self.lateral_accel_from_torque = CI.lateral_accel_from_torque() self.lateral_accel_from_torque = CI.lateral_accel_from_torque()
self.pid = PIDController(self.torque_params.kp, self.torque_params.ki, self.pid = PIDController(KP, KI, k_d=KD, rate=1/self.dt)
k_f=self.torque_params.kf)
self.update_limits() self.update_limits()
self.steering_angle_deadzone_deg = self.torque_params.steeringAngleDeadzoneDeg self.steering_angle_deadzone_deg = self.torque_params.steeringAngleDeadzoneDeg
self.LATACCEL_REQUEST_BUFFER_NUM_FRAMES = int(1 / self.dt)
self.requested_lateral_accel_buffer = deque([0.] * self.LATACCEL_REQUEST_BUFFER_NUM_FRAMES , maxlen=self.LATACCEL_REQUEST_BUFFER_NUM_FRAMES)
self.previous_measurement = 0.0
self.measurement_rate_filter = FirstOrderFilter(0.0, 1 / (2 * np.pi * (MAX_LAT_JERK_UP - 0.5)), self.dt)
def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction): def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction):
self.torque_params.latAccelFactor = latAccelFactor self.torque_params.latAccelFactor = latAccelFactor
@ -43,37 +53,48 @@ class LatControlTorque(LatControl):
self.pid.set_limits(self.lateral_accel_from_torque(self.steer_max, self.torque_params), self.pid.set_limits(self.lateral_accel_from_torque(self.steer_max, self.torque_params),
self.lateral_accel_from_torque(-self.steer_max, self.torque_params)) self.lateral_accel_from_torque(-self.steer_max, self.torque_params))
def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited): def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited, lat_delay):
pid_log = log.ControlsState.LateralTorqueState.new_message() pid_log = log.ControlsState.LateralTorqueState.new_message()
if not active: if not active:
output_torque = 0.0 output_torque = 0.0
pid_log.active = False pid_log.active = False
else: else:
actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) measured_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll)
roll_compensation = params.roll * ACCELERATION_DUE_TO_GRAVITY roll_compensation = params.roll * ACCELERATION_DUE_TO_GRAVITY
curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0))
desired_lateral_accel = desired_curvature * CS.vEgo ** 2
actual_lateral_accel = actual_curvature * CS.vEgo ** 2
lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2
low_speed_factor = np.interp(CS.vEgo, LOW_SPEED_X, LOW_SPEED_Y)**2 delay_frames = int(np.clip(lat_delay / self.dt, 1, self.LATACCEL_REQUEST_BUFFER_NUM_FRAMES))
setpoint = desired_lateral_accel + low_speed_factor * desired_curvature expected_lateral_accel = self.requested_lateral_accel_buffer[-delay_frames]
measurement = actual_lateral_accel + low_speed_factor * actual_curvature # TODO factor out lateral jerk from error to later replace it with delay independent alternative
gravity_adjusted_lateral_accel = desired_lateral_accel - roll_compensation future_desired_lateral_accel = desired_curvature * CS.vEgo ** 2
self.requested_lateral_accel_buffer.append(future_desired_lateral_accel)
gravity_adjusted_future_lateral_accel = future_desired_lateral_accel - roll_compensation
desired_lateral_jerk = (future_desired_lateral_accel - expected_lateral_accel) / lat_delay
measurement = measured_curvature * CS.vEgo ** 2
measurement_rate = self.measurement_rate_filter.update((measurement - self.previous_measurement) / self.dt)
self.previous_measurement = measurement
low_speed_factor = (np.interp(CS.vEgo, LOW_SPEED_X, LOW_SPEED_Y) / max(CS.vEgo, MIN_SPEED)) ** 2
setpoint = lat_delay * desired_lateral_jerk + expected_lateral_accel
error = setpoint - measurement
error_lsf = error + low_speed_factor / KP * error
# do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly
pid_log.error = float(setpoint - measurement) pid_log.error = float(error_lsf)
ff = gravity_adjusted_lateral_accel ff = gravity_adjusted_future_lateral_accel
# latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll # latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll
ff -= self.torque_params.latAccelOffset ff -= self.torque_params.latAccelOffset
ff += get_friction(desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) # TODO jerk is weighted by lat_delay for legacy reasons, but should be made independent of it
ff += get_friction(error, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params)
freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5
output_lataccel = self.pid.update(pid_log.error, output_lataccel = self.pid.update(pid_log.error,
feedforward=ff, -measurement_rate,
speed=CS.vEgo, feedforward=ff,
freeze_integrator=freeze_integrator) speed=CS.vEgo,
freeze_integrator=freeze_integrator)
output_torque = self.torque_from_lateral_accel(output_lataccel, self.torque_params) output_torque = self.torque_from_lateral_accel(output_lataccel, self.torque_params)
pid_log.active = True pid_log.active = True
@ -82,8 +103,8 @@ class LatControlTorque(LatControl):
pid_log.d = float(self.pid.d) pid_log.d = float(self.pid.d)
pid_log.f = float(self.pid.f) pid_log.f = float(self.pid.f)
pid_log.output = float(-output_torque) # TODO: log lat accel? pid_log.output = float(-output_torque) # TODO: log lat accel?
pid_log.actualLateralAccel = float(actual_lateral_accel) pid_log.actualLateralAccel = float(measurement)
pid_log.desiredLateralAccel = float(desired_lateral_accel) pid_log.desiredLateralAccel = float(setpoint)
pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited_by_safety, curvature_limited)) pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited_by_safety, curvature_limited))
# TODO left is positive in this convention # TODO left is positive in this convention

@ -50,7 +50,7 @@ class LongControl:
self.long_control_state = LongCtrlState.off self.long_control_state = LongCtrlState.off
self.pid = PIDController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV), self.pid = PIDController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV),
(CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV), (CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV),
k_f=CP.longitudinalTuning.kf, rate=1 / DT_CTRL) rate=1 / DT_CTRL)
self.last_output_accel = 0.0 self.last_output_accel = 0.0
def reset(self): def reset(self):

@ -7,6 +7,7 @@ from opendbc.car.toyota.values import CAR as TOYOTA
from opendbc.car.nissan.values import CAR as NISSAN from opendbc.car.nissan.values import CAR as NISSAN
from opendbc.car.gm.values import CAR as GM from opendbc.car.gm.values import CAR as GM
from opendbc.car.vehicle_model import VehicleModel from opendbc.car.vehicle_model import VehicleModel
from openpilot.common.realtime import DT_CTRL
from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID
from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque
from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle
@ -22,7 +23,7 @@ class TestLatControl:
CI = CarInterface(CP) CI = CarInterface(CP)
VM = VehicleModel(CP) VM = VehicleModel(CP)
controller = controller(CP.as_reader(), CI) controller = controller(CP.as_reader(), CI, DT_CTRL)
CS = car.CarState.new_message() CS = car.CarState.new_message()
CS.vEgo = 30 CS.vEgo = 30
@ -32,13 +33,13 @@ class TestLatControl:
# Saturate for curvature limited and controller limited # Saturate for curvature limited and controller limited
for _ in range(1000): for _ in range(1000):
_, _, lac_log = controller.update(True, CS, VM, params, False, 0, True) _, _, lac_log = controller.update(True, CS, VM, params, False, 0, True, 0.2)
assert lac_log.saturated assert lac_log.saturated
for _ in range(1000): for _ in range(1000):
_, _, lac_log = controller.update(True, CS, VM, params, False, 0, False) _, _, lac_log = controller.update(True, CS, VM, params, False, 0, False, 0.2)
assert not lac_log.saturated assert not lac_log.saturated
for _ in range(1000): for _ in range(1000):
_, _, lac_log = controller.update(True, CS, VM, params, False, 1, False) _, _, lac_log = controller.update(True, CS, VM, params, False, 1, False, 0.2)
assert lac_log.saturated assert lac_log.saturated

@ -25,13 +25,13 @@ from openpilot.selfdrive.modeld.runners.tinygrad_helpers import qcom_tensor_from
MODEL_WIDTH, MODEL_HEIGHT = DM_INPUT_SIZE MODEL_WIDTH, MODEL_HEIGHT = DM_INPUT_SIZE
CALIB_LEN = 3 CALIB_LEN = 3
FEATURE_LEN = 512 FEATURE_LEN = 512
OUTPUT_SIZE = 84 + FEATURE_LEN OUTPUT_SIZE = 83 + FEATURE_LEN
PROCESS_NAME = "selfdrive.modeld.dmonitoringmodeld" PROCESS_NAME = "selfdrive.modeld.dmonitoringmodeld"
SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') SEND_RAW_PRED = os.getenv('SEND_RAW_PRED')
MODEL_PKL_PATH = Path(__file__).parent / 'models/dmonitoring_model_tinygrad.pkl' MODEL_PKL_PATH = Path(__file__).parent / 'models/dmonitoring_model_tinygrad.pkl'
# TODO: slice from meta
class DriverStateResult(ctypes.Structure): class DriverStateResult(ctypes.Structure):
_fields_ = [ _fields_ = [
("face_orientation", ctypes.c_float*3), ("face_orientation", ctypes.c_float*3),
@ -46,8 +46,8 @@ class DriverStateResult(ctypes.Structure):
("left_blink_prob", ctypes.c_float), ("left_blink_prob", ctypes.c_float),
("right_blink_prob", ctypes.c_float), ("right_blink_prob", ctypes.c_float),
("sunglasses_prob", ctypes.c_float), ("sunglasses_prob", ctypes.c_float),
("occluded_prob", ctypes.c_float), ("_unused_c", ctypes.c_float),
("ready_prob", ctypes.c_float*4), ("_unused_d", ctypes.c_float*4),
("not_ready_prob", ctypes.c_float*2)] ("not_ready_prob", ctypes.c_float*2)]
@ -55,7 +55,6 @@ class DMonitoringModelResult(ctypes.Structure):
_fields_ = [ _fields_ = [
("driver_state_lhd", DriverStateResult), ("driver_state_lhd", DriverStateResult),
("driver_state_rhd", DriverStateResult), ("driver_state_rhd", DriverStateResult),
("poor_vision_prob", ctypes.c_float),
("wheel_on_right_prob", ctypes.c_float), ("wheel_on_right_prob", ctypes.c_float),
("features", ctypes.c_float*FEATURE_LEN)] ("features", ctypes.c_float*FEATURE_LEN)]
@ -107,8 +106,6 @@ def fill_driver_state(msg, ds_result: DriverStateResult):
msg.leftBlinkProb = float(sigmoid(ds_result.left_blink_prob)) msg.leftBlinkProb = float(sigmoid(ds_result.left_blink_prob))
msg.rightBlinkProb = float(sigmoid(ds_result.right_blink_prob)) msg.rightBlinkProb = float(sigmoid(ds_result.right_blink_prob))
msg.sunglassesProb = float(sigmoid(ds_result.sunglasses_prob)) msg.sunglassesProb = float(sigmoid(ds_result.sunglasses_prob))
msg.occludedProb = float(sigmoid(ds_result.occluded_prob))
msg.readyProb = [float(sigmoid(x)) for x in ds_result.ready_prob]
msg.notReadyProb = [float(sigmoid(x)) for x in ds_result.not_ready_prob] msg.notReadyProb = [float(sigmoid(x)) for x in ds_result.not_ready_prob]
@ -119,7 +116,6 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts:
ds.frameId = frame_id ds.frameId = frame_id
ds.modelExecutionTime = execution_time ds.modelExecutionTime = execution_time
ds.gpuExecutionTime = gpu_execution_time ds.gpuExecutionTime = gpu_execution_time
ds.poorVisionProb = float(sigmoid(model_result.poor_vision_prob))
ds.wheelOnRightProb = float(sigmoid(model_result.wheel_on_right_prob)) ds.wheelOnRightProb = float(sigmoid(model_result.wheel_on_right_prob))
ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b'' ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b''
fill_driver_state(ds.leftDriverData, model_result.driver_state_lhd) fill_driver_state(ds.leftDriverData, model_result.driver_state_lhd)

@ -62,6 +62,5 @@ Refer to **slice_outputs** and **parse_vision_outputs/parse_policy_outputs** in
* (deprecated) distracted probabilities: 2 * (deprecated) distracted probabilities: 2
* using phone probability: 1 * using phone probability: 1
* distracted probability: 1 * distracted probability: 1
* common outputs 2 * common outputs 1
* poor camera vision probability: 1
* left hand drive probability: 1 * left hand drive probability: 1

@ -1,2 +0,0 @@
fa69be01-b430-4504-9d72-7dcb058eb6dd
d9fb22d1c4fa3ca3d201dbc8edf1d0f0918e53e6

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:50efe6451a3fb3fa04b6bb0e846544533329bd46ecefe9e657e91214dee2aaeb oid sha256:9b2117ee4907add59e3fbe6829cda74e0ad71c0835b0ebb9373ba9425de0d336
size 7196502 size 7191776

@ -38,8 +38,6 @@ class DRIVER_MONITOR_SETTINGS:
self._EE_THRESH12 = 15.0 self._EE_THRESH12 = 15.0
self._EE_MAX_OFFSET1 = 0.06 self._EE_MAX_OFFSET1 = 0.06
self._EE_MIN_OFFSET1 = 0.025 self._EE_MIN_OFFSET1 = 0.025
self._EE_THRESH21 = 0.01
self._EE_THRESH22 = 0.35
self._POSE_PITCH_THRESHOLD = 0.3133 self._POSE_PITCH_THRESHOLD = 0.3133
self._POSE_PITCH_THRESHOLD_SLACK = 0.3237 self._POSE_PITCH_THRESHOLD_SLACK = 0.3237
@ -137,11 +135,8 @@ class DriverMonitoring:
self.pose = DriverPose(self.settings._POSE_OFFSET_MAX_COUNT) self.pose = DriverPose(self.settings._POSE_OFFSET_MAX_COUNT)
self.blink = DriverBlink() self.blink = DriverBlink()
self.eev1 = 0. self.eev1 = 0.
self.eev2 = 1.
self.ee1_offseter = RunningStatFilter(max_trackable=self.settings._POSE_OFFSET_MAX_COUNT) self.ee1_offseter = RunningStatFilter(max_trackable=self.settings._POSE_OFFSET_MAX_COUNT)
self.ee2_offseter = RunningStatFilter(max_trackable=self.settings._POSE_OFFSET_MAX_COUNT)
self.ee1_calibrated = False self.ee1_calibrated = False
self.ee2_calibrated = False
self.always_on = always_on self.always_on = always_on
self.distracted_types = [] self.distracted_types = []
@ -262,7 +257,7 @@ class DriverMonitoring:
driver_data = driver_state.rightDriverData if self.wheel_on_right else driver_state.leftDriverData driver_data = driver_state.rightDriverData if self.wheel_on_right else driver_state.leftDriverData
if not all(len(x) > 0 for x in (driver_data.faceOrientation, driver_data.facePosition, if not all(len(x) > 0 for x in (driver_data.faceOrientation, driver_data.facePosition,
driver_data.faceOrientationStd, driver_data.facePositionStd, driver_data.faceOrientationStd, driver_data.facePositionStd,
driver_data.readyProb, driver_data.notReadyProb)): driver_data.notReadyProb)):
return return
self.face_detected = driver_data.faceProb > self.settings._FACE_THRESHOLD self.face_detected = driver_data.faceProb > self.settings._FACE_THRESHOLD
@ -279,7 +274,6 @@ class DriverMonitoring:
self.blink.right = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) \ self.blink.right = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) \
* (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD)
self.eev1 = driver_data.notReadyProb[0] self.eev1 = driver_data.notReadyProb[0]
self.eev2 = driver_data.readyProb[0]
self.distracted_types = self._get_distracted_types() self.distracted_types = self._get_distracted_types()
self.driver_distracted = (DistractedType.DISTRACTED_E2E in self.distracted_types or DistractedType.DISTRACTED_POSE in self.distracted_types self.driver_distracted = (DistractedType.DISTRACTED_E2E in self.distracted_types or DistractedType.DISTRACTED_POSE in self.distracted_types
@ -293,12 +287,10 @@ class DriverMonitoring:
self.pose.pitch_offseter.push_and_update(self.pose.pitch) self.pose.pitch_offseter.push_and_update(self.pose.pitch)
self.pose.yaw_offseter.push_and_update(self.pose.yaw) self.pose.yaw_offseter.push_and_update(self.pose.yaw)
self.ee1_offseter.push_and_update(self.eev1) self.ee1_offseter.push_and_update(self.eev1)
self.ee2_offseter.push_and_update(self.eev2)
self.pose.calibrated = self.pose.pitch_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT and \ self.pose.calibrated = self.pose.pitch_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT and \
self.pose.yaw_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT self.pose.yaw_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT
self.ee1_calibrated = self.ee1_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT self.ee1_calibrated = self.ee1_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT
self.ee2_calibrated = self.ee2_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT
self.is_model_uncertain = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME self.is_model_uncertain = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME
self._set_timers(self.face_detected and not self.is_model_uncertain) self._set_timers(self.face_detected and not self.is_model_uncertain)

@ -25,7 +25,6 @@ def make_msg(face_detected, distracted=False, model_uncertain=False):
ds.leftDriverData.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain] ds.leftDriverData.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain]
ds.leftDriverData.facePositionStd = [1.*model_uncertain, 1.*model_uncertain] ds.leftDriverData.facePositionStd = [1.*model_uncertain, 1.*model_uncertain]
# TODO: test both separately when e2e is used # TODO: test both separately when e2e is used
ds.leftDriverData.readyProb = [0., 0., 0., 0.]
ds.leftDriverData.notReadyProb = [0., 0.] ds.leftDriverData.notReadyProb = [0., 0.]
return ds return ds

@ -1 +1 @@
afcab1abb62b9d5678342956cced4712f44e909e 55e82ab6370865a1427ebc1d559921a5354d9cbf

@ -42,6 +42,7 @@ sudo systemctl restart NetworkManager
sudo systemctl disable ssh-param-watcher.path sudo systemctl disable ssh-param-watcher.path
sudo systemctl disable ssh-param-watcher.service sudo systemctl disable ssh-param-watcher.service
sudo mount -o ro,remount / sudo mount -o ro,remount /
sudo systemctl stop power_monitor
while true; do while true; do
if ! sudo systemctl is-active -q ssh; then if ! sudo systemctl is-active -q ssh; then
@ -54,7 +55,6 @@ while true; do
# /data/ciui.py & # /data/ciui.py &
#fi #fi
awk '{print \$1}' /proc/uptime > /var/tmp/power_watchdog
sleep 5s sleep 5s
done done

@ -32,7 +32,7 @@ CPU usage budget
TEST_DURATION = 25 TEST_DURATION = 25
LOG_OFFSET = 8 LOG_OFFSET = 8
MAX_TOTAL_CPU = 300. # total for all 8 cores MAX_TOTAL_CPU = 315. # total for all 8 cores
PROCS = { PROCS = {
# Baseline CPU usage by process # Baseline CPU usage by process
"selfdrive.controls.controlsd": 16.0, "selfdrive.controls.controlsd": 16.0,
@ -42,7 +42,7 @@ PROCS = {
"./encoderd": 13.0, "./encoderd": 13.0,
"./camerad": 10.0, "./camerad": 10.0,
"selfdrive.controls.plannerd": 8.0, "selfdrive.controls.plannerd": 8.0,
"./ui": 18.0, "selfdrive.ui.ui": 24.0,
"system.sensord.sensord": 13.0, "system.sensord.sensord": 13.0,
"selfdrive.controls.radard": 2.0, "selfdrive.controls.radard": 2.0,
"selfdrive.modeld.modeld": 22.0, "selfdrive.modeld.modeld": 22.0,
@ -206,7 +206,8 @@ class TestOnroad:
result += "-------------- UI Draw Timing ------------------\n" result += "-------------- UI Draw Timing ------------------\n"
result += "------------------------------------------------\n" result += "------------------------------------------------\n"
ts = self.ts['uiDebug']['drawTimeMillis'] # skip first few frames -- connecting to vipc
ts = self.ts['uiDebug']['drawTimeMillis'][15:]
result += f"min {min(ts):.2f}ms\n" result += f"min {min(ts):.2f}ms\n"
result += f"max {max(ts):.2f}ms\n" result += f"max {max(ts):.2f}ms\n"
result += f"std {np.std(ts):.2f}ms\n" result += f"std {np.std(ts):.2f}ms\n"
@ -215,7 +216,7 @@ class TestOnroad:
print(result) print(result)
assert max(ts) < 250. assert max(ts) < 250.
assert np.mean(ts) < 10. assert np.mean(ts) < 20. # TODO: ~6-11ms, increase consistency
#self.assertLess(np.std(ts), 5.) #self.assertLess(np.std(ts), 5.)
# some slow frames are expected since camerad/modeld can preempt ui # some slow frames are expected since camerad/modeld can preempt ui
@ -285,7 +286,7 @@ class TestOnroad:
# check for big leaks. note that memory usage is # check for big leaks. note that memory usage is
# expected to go up while the MSGQ buffers fill up # expected to go up while the MSGQ buffers fill up
assert np.average(mems) <= 65, "Average memory usage above 65%" assert np.average(mems) <= 85, "Average memory usage above 85%"
assert np.max(np.diff(mems)) <= 4, "Max memory increase too high" assert np.max(np.diff(mems)) <= 4, "Max memory increase too high"
assert np.average(np.diff(mems)) <= 1, "Average memory increase too high" assert np.average(np.diff(mems)) <= 1, "Average memory increase too high"

@ -1,7 +1,7 @@
moc_* moc_*
*.moc *.moc
translations/main_test_en.* translations/test_en.*
ui ui
mui mui

@ -71,7 +71,7 @@ if GetOption('extras'):
raylib_libs = common + ["raylib"] raylib_libs = common + ["raylib"]
if arch == "larch64": if arch == "larch64":
raylib_libs += ["GLESv2", "wayland-client", "wayland-egl", "EGL"] raylib_libs += ["GLESv2", "EGL", "gbm", "drm"]
else: else:
raylib_libs += ["GL"] raylib_libs += ["GL"]

@ -5,6 +5,7 @@
#include "common/swaglog.h" #include "common/swaglog.h"
#include "common/util.h" #include "common/util.h"
#include "system/hardware/hw.h"
#include "third_party/raylib/include/raylib.h" #include "third_party/raylib/include/raylib.h"
int freshClone(); int freshClone();
@ -38,6 +39,27 @@ extern const uint8_t inter_ttf_end[] asm("_binary_selfdrive_ui_installer_inter_a
Font font; Font font;
std::vector<std::string> tici_prebuilt_branches = {"release3", "release-tizi", "release3-staging", "nightly", "nightly-dev"};
std::string migrated_branch;
void branchMigration() {
migrated_branch = BRANCH_STR;
cereal::InitData::DeviceType device_type = Hardware::get_device_type();
if (device_type == cereal::InitData::DeviceType::TICI) {
if (std::find(tici_prebuilt_branches.begin(), tici_prebuilt_branches.end(), BRANCH_STR) != tici_prebuilt_branches.end()) {
migrated_branch = "release-tici";
} else if (BRANCH_STR == "master") {
migrated_branch = "master-tici";
}
} else if (device_type == cereal::InitData::DeviceType::TIZI) {
if (BRANCH_STR == "release3") {
migrated_branch = "release-tizi";
} else if (BRANCH_STR == "release3-staging") {
migrated_branch = "release-tizi-staging";
}
}
}
void run(const char* cmd) { void run(const char* cmd) {
int err = std::system(cmd); int err = std::system(cmd);
assert(err == 0); assert(err == 0);
@ -87,7 +109,7 @@ int doInstall() {
int freshClone() { int freshClone() {
LOGD("Doing fresh clone"); LOGD("Doing fresh clone");
std::string cmd = util::string_format("git clone --progress %s -b %s --depth=1 --recurse-submodules %s 2>&1", std::string cmd = util::string_format("git clone --progress %s -b %s --depth=1 --recurse-submodules %s 2>&1",
GIT_URL.c_str(), BRANCH_STR.c_str(), TMP_INSTALL_PATH); GIT_URL.c_str(), migrated_branch.c_str(), TMP_INSTALL_PATH);
return executeGitCommand(cmd); return executeGitCommand(cmd);
} }
@ -95,11 +117,11 @@ int cachedFetch(const std::string &cache) {
LOGD("Fetching with cache: %s", cache.c_str()); LOGD("Fetching with cache: %s", cache.c_str());
run(util::string_format("cp -rp %s %s", cache.c_str(), TMP_INSTALL_PATH).c_str()); run(util::string_format("cp -rp %s %s", cache.c_str(), TMP_INSTALL_PATH).c_str());
run(util::string_format("cd %s && git remote set-branches --add origin %s", TMP_INSTALL_PATH, BRANCH_STR.c_str()).c_str()); run(util::string_format("cd %s && git remote set-branches --add origin %s", TMP_INSTALL_PATH, migrated_branch.c_str()).c_str());
renderProgress(10); renderProgress(10);
return executeGitCommand(util::string_format("cd %s && git fetch --progress origin %s 2>&1", TMP_INSTALL_PATH, BRANCH_STR.c_str())); return executeGitCommand(util::string_format("cd %s && git fetch --progress origin %s 2>&1", TMP_INSTALL_PATH, migrated_branch.c_str()));
} }
int executeGitCommand(const std::string &cmd) { int executeGitCommand(const std::string &cmd) {
@ -142,8 +164,8 @@ void cloneFinished(int exitCode) {
// ensure correct branch is checked out // ensure correct branch is checked out
int err = chdir(TMP_INSTALL_PATH); int err = chdir(TMP_INSTALL_PATH);
assert(err == 0); assert(err == 0);
run(("git checkout " + BRANCH_STR).c_str()); run(("git checkout " + migrated_branch).c_str());
run(("git reset --hard origin/" + BRANCH_STR).c_str()); run(("git reset --hard origin/" + migrated_branch).c_str());
run("git submodule update --init"); run("git submodule update --init");
// move into place // move into place
@ -193,6 +215,8 @@ int main(int argc, char *argv[]) {
font = LoadFontFromMemory(".ttf", inter_ttf, inter_ttf_end - inter_ttf, FONT_SIZE, NULL, 0); font = LoadFontFromMemory(".ttf", inter_ttf, inter_ttf_end - inter_ttf, FONT_SIZE, NULL, 0);
SetTextureFilter(font.texture, TEXTURE_FILTER_BILINEAR); SetTextureFilter(font.texture, TEXTURE_FILTER_BILINEAR);
branchMigration();
if (util::file_exists(CONTINUE_PATH)) { if (util::file_exists(CONTINUE_PATH)) {
finishInstall(); finishInstall();
} else { } else {

@ -8,7 +8,9 @@ from openpilot.selfdrive.ui.widgets.exp_mode_button import ExperimentalModeButto
from openpilot.selfdrive.ui.widgets.prime import PrimeWidget from openpilot.selfdrive.ui.widgets.prime import PrimeWidget
from openpilot.selfdrive.ui.widgets.setup import SetupWidget from openpilot.selfdrive.ui.widgets.setup import SetupWidget
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos, DEFAULT_TEXT_COLOR from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos
from openpilot.system.ui.lib.multilang import tr, trn
from openpilot.system.ui.widgets.label import gui_label
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
HEADER_HEIGHT = 80 HEADER_HEIGHT = 80
@ -35,12 +37,16 @@ class HomeLayout(Widget):
self.update_alert = UpdateAlert() self.update_alert = UpdateAlert()
self.offroad_alert = OffroadAlert() self.offroad_alert = OffroadAlert()
self._layout_widgets = {HomeLayoutState.UPDATE: self.update_alert, HomeLayoutState.ALERTS: self.offroad_alert}
self.current_state = HomeLayoutState.HOME self.current_state = HomeLayoutState.HOME
self.last_refresh = 0 self.last_refresh = 0
self.settings_callback: callable | None = None self.settings_callback: callable | None = None
self.update_available = False self.update_available = False
self.alert_count = 0 self.alert_count = 0
self._prev_update_available = False
self._prev_alerts_present = False
self.header_rect = rl.Rectangle(0, 0, 0, 0) self.header_rect = rl.Rectangle(0, 0, 0, 0)
self.content_rect = rl.Rectangle(0, 0, 0, 0) self.content_rect = rl.Rectangle(0, 0, 0, 0)
@ -57,17 +63,29 @@ class HomeLayout(Widget):
self._setup_callbacks() self._setup_callbacks()
def show_event(self): def show_event(self):
self._exp_mode_button.show_event()
self.last_refresh = time.monotonic() self.last_refresh = time.monotonic()
self._refresh() self._refresh()
def _setup_callbacks(self): def _setup_callbacks(self):
self.update_alert.set_dismiss_callback(lambda: self._set_state(HomeLayoutState.HOME)) self.update_alert.set_dismiss_callback(lambda: self._set_state(HomeLayoutState.HOME))
self.offroad_alert.set_dismiss_callback(lambda: self._set_state(HomeLayoutState.HOME)) self.offroad_alert.set_dismiss_callback(lambda: self._set_state(HomeLayoutState.HOME))
self._exp_mode_button.set_click_callback(lambda: self.settings_callback() if self.settings_callback else None)
def set_settings_callback(self, callback: Callable): def set_settings_callback(self, callback: Callable):
self.settings_callback = callback self.settings_callback = callback
def _set_state(self, state: HomeLayoutState): def _set_state(self, state: HomeLayoutState):
# propagate show/hide events
if state != self.current_state:
if state == HomeLayoutState.HOME:
self._exp_mode_button.show_event()
if state in self._layout_widgets:
self._layout_widgets[state].show_event()
if self.current_state in self._layout_widgets:
self._layout_widgets[self.current_state].hide_event()
self.current_state = state self.current_state = state
def _render(self, rect: rl.Rectangle): def _render(self, rect: rl.Rectangle):
@ -86,7 +104,7 @@ class HomeLayout(Widget):
elif self.current_state == HomeLayoutState.ALERTS: elif self.current_state == HomeLayoutState.ALERTS:
self._render_alerts_view() self._render_alerts_view()
def _update_layout_rects(self): def _update_state(self):
self.header_rect = rl.Rectangle( self.header_rect = rl.Rectangle(
self._rect.x + CONTENT_MARGIN, self._rect.y + CONTENT_MARGIN, self._rect.width - 2 * CONTENT_MARGIN, HEADER_HEIGHT self._rect.x + CONTENT_MARGIN, self._rect.y + CONTENT_MARGIN, self._rect.width - 2 * CONTENT_MARGIN, HEADER_HEIGHT
) )
@ -124,36 +142,43 @@ class HomeLayout(Widget):
def _render_header(self): def _render_header(self):
font = gui_app.font(FontWeight.MEDIUM) font = gui_app.font(FontWeight.MEDIUM)
version_text_width = self.header_rect.width
# Update notification button # Update notification button
if self.update_available: if self.update_available:
version_text_width -= self.update_notif_rect.width
# Highlight if currently viewing updates # Highlight if currently viewing updates
highlight_color = rl.Color(255, 140, 40, 255) if self.current_state == HomeLayoutState.UPDATE else rl.Color(255, 102, 0, 255) highlight_color = rl.Color(75, 95, 255, 255) if self.current_state == HomeLayoutState.UPDATE else rl.Color(54, 77, 239, 255)
rl.draw_rectangle_rounded(self.update_notif_rect, 0.3, 10, highlight_color) rl.draw_rectangle_rounded(self.update_notif_rect, 0.3, 10, highlight_color)
text = "UPDATE" text = tr("UPDATE")
text_width = measure_text_cached(font, text, HEAD_BUTTON_FONT_SIZE).x text_size = measure_text_cached(font, text, HEAD_BUTTON_FONT_SIZE)
text_x = self.update_notif_rect.x + (self.update_notif_rect.width - text_width) // 2 text_x = self.update_notif_rect.x + (self.update_notif_rect.width - text_size.x) // 2
text_y = self.update_notif_rect.y + (self.update_notif_rect.height - HEAD_BUTTON_FONT_SIZE) // 2 text_y = self.update_notif_rect.y + (self.update_notif_rect.height - text_size.y) // 2
rl.draw_text_ex(font, text, rl.Vector2(int(text_x), int(text_y)), HEAD_BUTTON_FONT_SIZE, 0, rl.WHITE) rl.draw_text_ex(font, text, rl.Vector2(int(text_x), int(text_y)), HEAD_BUTTON_FONT_SIZE, 0, rl.WHITE)
# Alert notification button # Alert notification button
if self.alert_count > 0: if self.alert_count > 0:
version_text_width -= self.alert_notif_rect.width
# Highlight if currently viewing alerts # Highlight if currently viewing alerts
highlight_color = rl.Color(255, 70, 70, 255) if self.current_state == HomeLayoutState.ALERTS else rl.Color(226, 44, 44, 255) highlight_color = rl.Color(255, 70, 70, 255) if self.current_state == HomeLayoutState.ALERTS else rl.Color(226, 44, 44, 255)
rl.draw_rectangle_rounded(self.alert_notif_rect, 0.3, 10, highlight_color) rl.draw_rectangle_rounded(self.alert_notif_rect, 0.3, 10, highlight_color)
alert_text = f"{self.alert_count} ALERT{'S' if self.alert_count > 1 else ''}" alert_text = trn("{} ALERT", "{} ALERTS", self.alert_count).format(self.alert_count)
text_width = measure_text_cached(font, alert_text, HEAD_BUTTON_FONT_SIZE).x text_size = measure_text_cached(font, alert_text, HEAD_BUTTON_FONT_SIZE)
text_x = self.alert_notif_rect.x + (self.alert_notif_rect.width - text_width) // 2 text_x = self.alert_notif_rect.x + (self.alert_notif_rect.width - text_size.x) // 2
text_y = self.alert_notif_rect.y + (self.alert_notif_rect.height - HEAD_BUTTON_FONT_SIZE) // 2 text_y = self.alert_notif_rect.y + (self.alert_notif_rect.height - text_size.y) // 2
rl.draw_text_ex(font, alert_text, rl.Vector2(int(text_x), int(text_y)), HEAD_BUTTON_FONT_SIZE, 0, rl.WHITE) rl.draw_text_ex(font, alert_text, rl.Vector2(int(text_x), int(text_y)), HEAD_BUTTON_FONT_SIZE, 0, rl.WHITE)
# Version text (right aligned) # Version text (right aligned)
version_text = self._get_version_text() if self.update_available or self.alert_count > 0:
text_width = measure_text_cached(gui_app.font(FontWeight.NORMAL), version_text, 48).x version_text_width -= SPACING * 1.5
version_x = self.header_rect.x + self.header_rect.width - text_width
version_y = self.header_rect.y + (self.header_rect.height - 48) // 2 version_rect = rl.Rectangle(self.header_rect.x + self.header_rect.width - version_text_width, self.header_rect.y,
rl.draw_text_ex(gui_app.font(FontWeight.NORMAL), version_text, rl.Vector2(int(version_x), int(version_y)), 48, 0, DEFAULT_TEXT_COLOR) version_text_width, self.header_rect.height)
gui_label(version_rect, self._get_version_text(), 48, rl.WHITE, alignment=rl.GuiTextAlignment.TEXT_ALIGN_RIGHT)
def _render_home_content(self): def _render_home_content(self):
self._render_left_column() self._render_left_column()
@ -185,19 +210,22 @@ class HomeLayout(Widget):
def _refresh(self): def _refresh(self):
# TODO: implement _update_state with a timer # TODO: implement _update_state with a timer
self.update_available = self.update_alert.refresh() update_available = self.update_alert.refresh()
self.alert_count = self.offroad_alert.refresh() alert_count = self.offroad_alert.refresh()
self._update_state_priority(self.update_available, self.alert_count > 0) alerts_present = alert_count > 0
def _update_state_priority(self, update_available: bool, alerts_present: bool):
current_state = self.current_state
# Show panels on transition from no alert/update to any alerts/update
if not update_available and not alerts_present: if not update_available and not alerts_present:
self.current_state = HomeLayoutState.HOME self._set_state(HomeLayoutState.HOME)
elif update_available and (current_state == HomeLayoutState.HOME or (not alerts_present and current_state == HomeLayoutState.ALERTS)): elif update_available and ((not self._prev_update_available) or (not alerts_present and self.current_state == HomeLayoutState.ALERTS)):
self.current_state = HomeLayoutState.UPDATE self._set_state(HomeLayoutState.UPDATE)
elif alerts_present and (current_state == HomeLayoutState.HOME or (not update_available and current_state == HomeLayoutState.UPDATE)): elif alerts_present and ((not self._prev_alerts_present) or (not update_available and self.current_state == HomeLayoutState.UPDATE)):
self.current_state = HomeLayoutState.ALERTS self._set_state(HomeLayoutState.ALERTS)
self.update_available = update_available
self.alert_count = alert_count
self._prev_update_available = update_available
self._prev_alerts_present = alerts_present
def _get_version_text(self) -> str: def _get_version_text(self) -> str:
brand = "openpilot" brand = "openpilot"

@ -8,10 +8,7 @@ from openpilot.selfdrive.ui.layouts.settings.settings import SettingsLayout, Pan
from openpilot.selfdrive.ui.onroad.augmented_road_view import AugmentedRoadView from openpilot.selfdrive.ui.onroad.augmented_road_view import AugmentedRoadView
from openpilot.selfdrive.ui.ui_state import device, ui_state from openpilot.selfdrive.ui.ui_state import device, ui_state
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.selfdrive.ui.layouts.onboarding import OnboardingWindow
ONROAD_FPS = 20
OFFROAD_FPS = 60
class MainState(IntEnum): class MainState(IntEnum):
@ -30,8 +27,6 @@ class MainLayout(Widget):
self._current_mode = MainState.HOME self._current_mode = MainState.HOME
self._prev_onroad = False self._prev_onroad = False
gui_app.set_target_fps(OFFROAD_FPS)
# Initialize layouts # Initialize layouts
self._layouts = {MainState.HOME: HomeLayout(), MainState.SETTINGS: SettingsLayout(), MainState.ONROAD: AugmentedRoadView()} self._layouts = {MainState.HOME: HomeLayout(), MainState.SETTINGS: SettingsLayout(), MainState.ONROAD: AugmentedRoadView()}
@ -41,14 +36,21 @@ class MainLayout(Widget):
# Set callbacks # Set callbacks
self._setup_callbacks() self._setup_callbacks()
# Start onboarding if terms or training not completed
self._onboarding_window = OnboardingWindow()
if not self._onboarding_window.completed:
gui_app.set_modal_overlay(self._onboarding_window)
def _render(self, _): def _render(self, _):
self._handle_onroad_transition() self._handle_onroad_transition()
self._render_main_content() self._render_main_content()
def _setup_callbacks(self): def _setup_callbacks(self):
self._sidebar.set_callbacks(on_settings=self._on_settings_clicked, self._sidebar.set_callbacks(on_settings=self._on_settings_clicked,
on_flag=self._on_bookmark_clicked) on_flag=self._on_bookmark_clicked,
open_settings=lambda: self.open_settings(PanelType.TOGGLES))
self._layouts[MainState.HOME]._setup_widget.set_open_settings_callback(lambda: self.open_settings(PanelType.FIREHOSE)) self._layouts[MainState.HOME]._setup_widget.set_open_settings_callback(lambda: self.open_settings(PanelType.FIREHOSE))
self._layouts[MainState.HOME].set_settings_callback(lambda: self.open_settings(PanelType.TOGGLES))
self._layouts[MainState.SETTINGS].set_callbacks(on_close=self._set_mode_for_state) self._layouts[MainState.SETTINGS].set_callbacks(on_close=self._set_mode_for_state)
self._layouts[MainState.ONROAD].set_click_callback(self._on_onroad_clicked) self._layouts[MainState.ONROAD].set_click_callback(self._on_onroad_clicked)
device.add_interactive_timeout_callback(self._set_mode_for_state) device.add_interactive_timeout_callback(self._set_mode_for_state)
@ -81,9 +83,6 @@ class MainLayout(Widget):
self._current_mode = layout self._current_mode = layout
self._layouts[self._current_mode].show_event() self._layouts[self._current_mode].show_event()
# No need to draw onroad faster than source (model at 20Hz) and prevents screen tearing
gui_app.set_target_fps(ONROAD_FPS if self._current_mode == MainState.ONROAD else OFFROAD_FPS)
def open_settings(self, panel_type: PanelType): def open_settings(self, panel_type: PanelType):
self._layouts[MainState.SETTINGS].set_current_panel(panel_type) self._layouts[MainState.SETTINGS].set_current_panel(panel_type)
self._set_current_layout(MainState.SETTINGS) self._set_current_layout(MainState.SETTINGS)

@ -0,0 +1,214 @@
import os
import re
import threading
from enum import IntEnum
import pyray as rl
from openpilot.common.basedir import BASEDIR
from openpilot.system.ui.lib.application import FontWeight, gui_app
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.button import Button, ButtonStyle
from openpilot.system.ui.widgets.label import Label
from openpilot.selfdrive.ui.ui_state import ui_state
DEBUG = False
STEP_RECTS = [rl.Rectangle(104, 800, 633, 175), rl.Rectangle(1835, 0, 2159, 1080), rl.Rectangle(1835, 0, 2156, 1080),
rl.Rectangle(1526, 473, 427, 472), rl.Rectangle(1643, 441, 217, 223), rl.Rectangle(1835, 0, 2155, 1080),
rl.Rectangle(1786, 591, 267, 236), rl.Rectangle(1353, 0, 804, 1080), rl.Rectangle(1458, 485, 633, 211),
rl.Rectangle(95, 794, 1158, 187), rl.Rectangle(1560, 170, 392, 397), rl.Rectangle(1835, 0, 2159, 1080),
rl.Rectangle(1351, 0, 807, 1080), rl.Rectangle(1835, 0, 2158, 1080), rl.Rectangle(1531, 82, 441, 920),
rl.Rectangle(1336, 438, 490, 393), rl.Rectangle(1835, 0, 2159, 1080), rl.Rectangle(1835, 0, 2159, 1080),
rl.Rectangle(87, 795, 1187, 186)]
DM_RECORD_STEP = 9
DM_RECORD_YES_RECT = rl.Rectangle(695, 794, 558, 187)
RESTART_TRAINING_RECT = rl.Rectangle(87, 795, 472, 186)
class OnboardingState(IntEnum):
TERMS = 0
ONBOARDING = 1
DECLINE = 2
class TrainingGuide(Widget):
def __init__(self, completed_callback=None):
super().__init__()
self._completed_callback = completed_callback
self._step = 0
self._load_image_paths()
# Load first image now so we show something immediately
self._textures = [gui_app.texture(self._image_paths[0])]
self._image_objs = []
threading.Thread(target=self._preload_thread, daemon=True).start()
def _load_image_paths(self):
paths = [fn for fn in os.listdir(os.path.join(BASEDIR, "selfdrive/assets/training")) if re.match(r'^step\d*\.png$', fn)]
paths = sorted(paths, key=lambda x: int(re.search(r'\d+', x).group()))
self._image_paths = [os.path.join(BASEDIR, "selfdrive/assets/training", fn) for fn in paths]
def _preload_thread(self):
# PNG loading is slow in raylib, so we preload in a thread and upload to GPU in main thread
# We've already loaded the first image on init
for path in self._image_paths[1:]:
self._image_objs.append(gui_app._load_image_from_path(path))
def _handle_mouse_release(self, mouse_pos):
if rl.check_collision_point_rec(mouse_pos, STEP_RECTS[self._step]):
# Record DM camera?
if self._step == DM_RECORD_STEP:
yes = rl.check_collision_point_rec(mouse_pos, DM_RECORD_YES_RECT)
print(f"putting RecordFront to {yes}")
ui_state.params.put_bool("RecordFront", yes)
# Restart training?
elif self._step == len(self._image_paths) - 1:
if rl.check_collision_point_rec(mouse_pos, RESTART_TRAINING_RECT):
self._step = -1
self._step += 1
# Finished?
if self._step >= len(self._image_paths):
self._step = 0
if self._completed_callback:
self._completed_callback()
def _update_state(self):
if len(self._image_objs):
self._textures.append(gui_app._load_texture_from_image(self._image_objs.pop(0)))
def _render(self, _):
# Safeguard against fast tapping
step = min(self._step, len(self._textures) - 1)
rl.draw_texture(self._textures[step], 0, 0, rl.WHITE)
# progress bar
if 0 < step < len(STEP_RECTS) - 1:
h = 20
w = int((step / (len(STEP_RECTS) - 1)) * self._rect.width)
rl.draw_rectangle(int(self._rect.x), int(self._rect.y + self._rect.height - h),
w, h, rl.Color(70, 91, 234, 255))
if DEBUG:
rl.draw_rectangle_lines_ex(STEP_RECTS[step], 3, rl.RED)
return -1
class TermsPage(Widget):
def __init__(self, on_accept=None, on_decline=None):
super().__init__()
self._on_accept = on_accept
self._on_decline = on_decline
self._title = Label(tr("Welcome to openpilot"), font_size=90, font_weight=FontWeight.BOLD, text_alignment=rl.GuiTextAlignment.TEXT_ALIGN_LEFT)
self._desc = Label(tr("You must accept the Terms and Conditions to use openpilot. Read the latest terms at https://comma.ai/terms before continuing."),
font_size=90, font_weight=FontWeight.MEDIUM, text_alignment=rl.GuiTextAlignment.TEXT_ALIGN_LEFT)
self._decline_btn = Button(tr("Decline"), click_callback=on_decline)
self._accept_btn = Button(tr("Agree"), button_style=ButtonStyle.PRIMARY, click_callback=on_accept)
def _render(self, _):
welcome_x = self._rect.x + 165
welcome_y = self._rect.y + 165
welcome_rect = rl.Rectangle(welcome_x, welcome_y, self._rect.width - welcome_x, 90)
self._title.render(welcome_rect)
desc_x = welcome_x
# TODO: Label doesn't top align when wrapping
desc_y = welcome_y - 100
desc_rect = rl.Rectangle(desc_x, desc_y, self._rect.width - desc_x, self._rect.height - desc_y - 250)
self._desc.render(desc_rect)
btn_y = self._rect.y + self._rect.height - 160 - 45
btn_width = (self._rect.width - 45 * 3) / 2
self._decline_btn.render(rl.Rectangle(self._rect.x + 45, btn_y, btn_width, 160))
self._accept_btn.render(rl.Rectangle(self._rect.x + 45 * 2 + btn_width, btn_y, btn_width, 160))
if DEBUG:
rl.draw_rectangle_lines_ex(welcome_rect, 3, rl.RED)
rl.draw_rectangle_lines_ex(desc_rect, 3, rl.RED)
return -1
class DeclinePage(Widget):
def __init__(self, back_callback=None):
super().__init__()
self._text = Label(tr("You must accept the Terms and Conditions in order to use openpilot."),
font_size=90, font_weight=FontWeight.MEDIUM, text_alignment=rl.GuiTextAlignment.TEXT_ALIGN_LEFT)
self._back_btn = Button(tr("Back"), click_callback=back_callback)
self._uninstall_btn = Button(tr("Decline, uninstall openpilot"), button_style=ButtonStyle.DANGER,
click_callback=self._on_uninstall_clicked)
def _on_uninstall_clicked(self):
ui_state.params.put_bool("DoUninstall", True)
gui_app.request_close()
def _render(self, _):
btn_y = self._rect.y + self._rect.height - 160 - 45
btn_width = (self._rect.width - 45 * 3) / 2
self._back_btn.render(rl.Rectangle(self._rect.x + 45, btn_y, btn_width, 160))
self._uninstall_btn.render(rl.Rectangle(self._rect.x + 45 * 2 + btn_width, btn_y, btn_width, 160))
# text rect in middle of top and button
text_height = btn_y - (200 + 45)
text_rect = rl.Rectangle(self._rect.x + 165, self._rect.y + (btn_y - text_height) / 2 + 10, self._rect.width - (165 * 2), text_height)
if DEBUG:
rl.draw_rectangle_lines_ex(text_rect, 3, rl.RED)
self._text.render(text_rect)
class OnboardingWindow(Widget):
def __init__(self):
super().__init__()
self._current_terms_version = ui_state.params.get("TermsVersion")
self._current_training_version = ui_state.params.get("TrainingVersion")
self._accepted_terms: bool = ui_state.params.get("HasAcceptedTerms") == self._current_terms_version
self._training_done: bool = ui_state.params.get("CompletedTrainingVersion") == self._current_training_version
self._state = OnboardingState.TERMS if not self._accepted_terms else OnboardingState.ONBOARDING
# Windows
self._terms = TermsPage(on_accept=self._on_terms_accepted, on_decline=self._on_terms_declined)
self._training_guide: TrainingGuide | None = None
self._decline_page = DeclinePage(back_callback=self._on_decline_back)
@property
def completed(self) -> bool:
return self._accepted_terms and self._training_done
def _on_terms_declined(self):
self._state = OnboardingState.DECLINE
def _on_decline_back(self):
self._state = OnboardingState.TERMS
def _on_terms_accepted(self):
ui_state.params.put("HasAcceptedTerms", self._current_terms_version)
self._state = OnboardingState.ONBOARDING
if self._training_done:
gui_app.set_modal_overlay(None)
def _on_completed_training(self):
ui_state.params.put("CompletedTrainingVersion", self._current_training_version)
gui_app.set_modal_overlay(None)
def _render(self, _):
if self._training_guide is None:
self._training_guide = TrainingGuide(completed_callback=self._on_completed_training)
if self._state == OnboardingState.TERMS:
self._terms.render(self._rect)
if self._state == OnboardingState.ONBOARDING:
self._training_guide.render(self._rect)
elif self._state == OnboardingState.DECLINE:
self._decline_page.render(self._rect)
return -1

@ -1,20 +1,29 @@
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.selfdrive.ui.widgets.ssh_key import ssh_key_item from openpilot.selfdrive.ui.widgets.ssh_key import ssh_key_item
from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.list_view import toggle_item from openpilot.system.ui.widgets.list_view import toggle_item
from openpilot.system.ui.widgets.scroller import Scroller from openpilot.system.ui.widgets.scroller import Scroller
from openpilot.system.ui.widgets.confirm_dialog import ConfirmDialog
from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.widgets import DialogResult
# Description constants # Description constants
DESCRIPTIONS = { DESCRIPTIONS = {
'enable_adb': ( 'enable_adb': tr(
"ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. " + "ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. " +
"See https://docs.comma.ai/how-to/connect-to-comma for more info." "See https://docs.comma.ai/how-to/connect-to-comma for more info."
), ),
'joystick_debug_mode': "Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)", 'ssh_key': tr(
'ssh_key': (
"Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username " + "Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username " +
"other than your own. A comma employee will NEVER ask you to add their GitHub username." "other than your own. A comma employee will NEVER ask you to add their GitHub username."
), ),
'alpha_longitudinal': tr(
"<b>WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).</b><br><br>" +
"On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. " +
"Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha."
),
} }
@ -22,40 +31,143 @@ class DeveloperLayout(Widget):
def __init__(self): def __init__(self):
super().__init__() super().__init__()
self._params = Params() self._params = Params()
self._is_release = self._params.get_bool("IsReleaseBranch")
# Build items and keep references for callbacks/state updates
self._adb_toggle = toggle_item(
tr("Enable ADB"),
description=DESCRIPTIONS["enable_adb"],
initial_state=self._params.get_bool("AdbEnabled"),
callback=self._on_enable_adb,
enabled=ui_state.is_offroad,
)
# SSH enable toggle + SSH key management
self._ssh_toggle = toggle_item(
tr("Enable SSH"),
description="",
initial_state=self._params.get_bool("SshEnabled"),
callback=self._on_enable_ssh,
)
self._ssh_keys = ssh_key_item("SSH Keys", description=DESCRIPTIONS["ssh_key"])
self._joystick_toggle = toggle_item(
tr("Joystick Debug Mode"),
description="",
initial_state=self._params.get_bool("JoystickDebugMode"),
callback=self._on_joystick_debug_mode,
enabled=ui_state.is_offroad,
)
self._long_maneuver_toggle = toggle_item(
tr("Longitudinal Maneuver Mode"),
description="",
initial_state=self._params.get_bool("LongitudinalManeuverMode"),
callback=self._on_long_maneuver_mode,
)
self._alpha_long_toggle = toggle_item(
tr("openpilot Longitudinal Control (Alpha)"),
description=DESCRIPTIONS["alpha_longitudinal"],
initial_state=self._params.get_bool("AlphaLongitudinalEnabled"),
callback=self._on_alpha_long_enabled,
enabled=lambda: not ui_state.engaged,
)
self._alpha_long_toggle.set_description(self._alpha_long_toggle.description + " Changing this setting will restart openpilot if the car is powered on.")
items = [ items = [
toggle_item( self._adb_toggle,
"Enable ADB", self._ssh_toggle,
description=DESCRIPTIONS["enable_adb"], self._ssh_keys,
initial_state=self._params.get_bool("AdbEnabled"), self._joystick_toggle,
callback=self._on_enable_adb, self._long_maneuver_toggle,
), self._alpha_long_toggle,
ssh_key_item("SSH Key", description=DESCRIPTIONS["ssh_key"]),
toggle_item(
"Joystick Debug Mode",
description=DESCRIPTIONS["joystick_debug_mode"],
initial_state=self._params.get_bool("JoystickDebugMode"),
callback=self._on_joystick_debug_mode,
),
toggle_item(
"Longitudinal Maneuver Mode",
description="",
initial_state=self._params.get_bool("LongitudinalManeuverMode"),
callback=self._on_long_maneuver_mode,
),
toggle_item(
"openpilot Longitudinal Control (Alpha)",
description="",
initial_state=self._params.get_bool("AlphaLongitudinalEnabled"),
callback=self._on_alpha_long_enabled,
),
] ]
self._scroller = Scroller(items, line_separator=True, spacing=0) self._scroller = Scroller(items, line_separator=True, spacing=0)
# Toggles should be not available to change in onroad state
ui_state.add_offroad_transition_callback(self._update_toggles)
def _render(self, rect): def _render(self, rect):
self._scroller.render(rect) self._scroller.render(rect)
def _on_enable_adb(self): pass def show_event(self):
def _on_joystick_debug_mode(self): pass self._scroller.show_event()
def _on_long_maneuver_mode(self): pass self._update_toggles()
def _on_alpha_long_enabled(self): pass
def _update_toggles(self):
ui_state.update_params()
# Hide non-release toggles on release builds
# TODO: we can do an onroad cycle, but alpha long toggle requires a deinit function to re-enable radar and not fault
for item in (self._adb_toggle, self._joystick_toggle, self._long_maneuver_toggle, self._alpha_long_toggle):
item.set_visible(not self._is_release)
# CP gating
if ui_state.CP is not None:
alpha_avail = ui_state.CP.alphaLongitudinalAvailable
if not alpha_avail or self._is_release:
self._alpha_long_toggle.set_visible(False)
self._params.remove("AlphaLongitudinalEnabled")
else:
self._alpha_long_toggle.set_visible(True)
long_man_enabled = ui_state.has_longitudinal_control and ui_state.is_offroad()
self._long_maneuver_toggle.action_item.set_enabled(long_man_enabled)
if not long_man_enabled:
self._long_maneuver_toggle.action_item.set_state(False)
self._params.put_bool("LongitudinalManeuverMode", False)
else:
self._long_maneuver_toggle.action_item.set_enabled(False)
self._alpha_long_toggle.set_visible(False)
# TODO: make a param control list item so we don't need to manage internal state as much here
# refresh toggles from params to mirror external changes
for key, item in (
("AdbEnabled", self._adb_toggle),
("SshEnabled", self._ssh_toggle),
("JoystickDebugMode", self._joystick_toggle),
("LongitudinalManeuverMode", self._long_maneuver_toggle),
("AlphaLongitudinalEnabled", self._alpha_long_toggle),
):
item.action_item.set_state(self._params.get_bool(key))
def _on_enable_adb(self, state: bool):
self._params.put_bool("AdbEnabled", state)
def _on_enable_ssh(self, state: bool):
self._params.put_bool("SshEnabled", state)
def _on_joystick_debug_mode(self, state: bool):
self._params.put_bool("JoystickDebugMode", state)
self._params.put_bool("LongitudinalManeuverMode", False)
self._long_maneuver_toggle.action_item.set_state(False)
def _on_long_maneuver_mode(self, state: bool):
self._params.put_bool("LongitudinalManeuverMode", state)
self._params.put_bool("JoystickDebugMode", False)
self._joystick_toggle.action_item.set_state(False)
def _on_alpha_long_enabled(self, state: bool):
if state:
def confirm_callback(result: int):
if result == DialogResult.CONFIRM:
self._params.put_bool("AlphaLongitudinalEnabled", True)
self._params.put_bool("OnroadCycleRequested", True)
self._update_toggles()
else:
self._alpha_long_toggle.action_item.set_state(False)
# show confirmation dialog
content = (f"<h1>{self._alpha_long_toggle.title}</h1><br>" +
f"<p>{self._alpha_long_toggle.description}</p>")
dlg = ConfirmDialog(content, tr("Enable"), rich=True)
gui_app.set_modal_overlay(dlg, callback=confirm_callback)
else:
self._params.put_bool("AlphaLongitudinalEnabled", False)
self._params.put_bool("OnroadCycleRequested", True)
self._update_toggles()

@ -1,29 +1,31 @@
import os import os
import json import json
import math
from cereal import messaging, log
from openpilot.common.basedir import BASEDIR from openpilot.common.basedir import BASEDIR
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog
from openpilot.selfdrive.ui.onroad.driver_camera_dialog import DriverCameraDialog from openpilot.selfdrive.ui.onroad.driver_camera_dialog import DriverCameraDialog
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.selfdrive.ui.layouts.onboarding import TrainingGuide
from openpilot.selfdrive.ui.widgets.pairing_dialog import PairingDialog from openpilot.selfdrive.ui.widgets.pairing_dialog import PairingDialog
from openpilot.system.hardware import TICI from openpilot.system.hardware import TICI
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.widgets import Widget, DialogResult from openpilot.system.ui.widgets import Widget, DialogResult
from openpilot.system.ui.widgets.confirm_dialog import confirm_dialog, alert_dialog from openpilot.system.ui.widgets.confirm_dialog import ConfirmDialog, alert_dialog
from openpilot.system.ui.widgets.html_render import HtmlRenderer from openpilot.system.ui.widgets.html_render import HtmlModal
from openpilot.system.ui.widgets.list_view import text_item, button_item, dual_button_item from openpilot.system.ui.widgets.list_view import text_item, button_item, dual_button_item
from openpilot.system.ui.widgets.option_dialog import MultiOptionDialog from openpilot.system.ui.widgets.option_dialog import MultiOptionDialog
from openpilot.system.ui.widgets.scroller import Scroller from openpilot.system.ui.widgets.scroller import Scroller
# Description constants # Description constants
DESCRIPTIONS = { DESCRIPTIONS = {
'pair_device': "Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.", 'pair_device': tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer."),
'driver_camera': "Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)", 'driver_camera': tr("Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)"),
'reset_calibration': ( 'reset_calibration': tr("openpilot requires the device to be mounted within 4° left or right and within 5° up or 9° down."),
"openpilot requires the device to be mounted within 4° left or right and within 5° " + 'review_guide': tr("Review the rules, features, and limitations of openpilot"),
"up or 9° down. openpilot is continuously calibrating, resetting is rarely required."
),
'review_guide': "Review the rules, features, and limitations of openpilot",
} }
@ -35,32 +37,47 @@ class DeviceLayout(Widget):
self._select_language_dialog: MultiOptionDialog | None = None self._select_language_dialog: MultiOptionDialog | None = None
self._driver_camera: DriverCameraDialog | None = None self._driver_camera: DriverCameraDialog | None = None
self._pair_device_dialog: PairingDialog | None = None self._pair_device_dialog: PairingDialog | None = None
self._fcc_dialog: HtmlRenderer | None = None self._fcc_dialog: HtmlModal | None = None
self._training_guide: TrainingGuide | None = None
items = self._initialize_items() items = self._initialize_items()
self._scroller = Scroller(items, line_separator=True, spacing=0) self._scroller = Scroller(items, line_separator=True, spacing=0)
ui_state.add_offroad_transition_callback(self._offroad_transition)
def _initialize_items(self): def _initialize_items(self):
dongle_id = self._params.get("DongleId") or "N/A" dongle_id = self._params.get("DongleId") or tr("N/A")
serial = self._params.get("HardwareSerial") or "N/A" serial = self._params.get("HardwareSerial") or tr("N/A")
self._pair_device_btn = button_item("Pair Device", "PAIR", DESCRIPTIONS['pair_device'], callback=self._pair_device) self._pair_device_btn = button_item(tr("Pair Device"), tr("PAIR"), DESCRIPTIONS['pair_device'], callback=self._pair_device)
self._pair_device_btn.set_visible(lambda: not ui_state.prime_state.is_paired()) self._pair_device_btn.set_visible(lambda: not ui_state.prime_state.is_paired())
self._reset_calib_btn = button_item(tr("Reset Calibration"), tr("RESET"), DESCRIPTIONS['reset_calibration'], callback=self._reset_calibration_prompt)
self._reset_calib_btn.set_description_opened_callback(self._update_calib_description)
self._power_off_btn = dual_button_item(tr("Reboot"), tr("Power Off"), left_callback=self._reboot_prompt, right_callback=self._power_off_prompt)
items = [ items = [
text_item("Dongle ID", dongle_id), text_item(tr("Dongle ID"), dongle_id),
text_item("Serial", serial), text_item(tr("Serial"), serial),
self._pair_device_btn, self._pair_device_btn,
button_item("Driver Camera", "PREVIEW", DESCRIPTIONS['driver_camera'], callback=self._show_driver_camera, enabled=ui_state.is_offroad), button_item(tr("Driver Camera"), tr("PREVIEW"), DESCRIPTIONS['driver_camera'], callback=self._show_driver_camera, enabled=ui_state.is_offroad),
button_item("Reset Calibration", "RESET", DESCRIPTIONS['reset_calibration'], callback=self._reset_calibration_prompt), self._reset_calib_btn,
regulatory_btn := button_item("Regulatory", "VIEW", callback=self._on_regulatory), button_item(tr("Review Training Guide"), tr("REVIEW"), DESCRIPTIONS['review_guide'], self._on_review_training_guide, enabled=ui_state.is_offroad),
button_item("Review Training Guide", "REVIEW", DESCRIPTIONS['review_guide'], self._on_review_training_guide), regulatory_btn := button_item(tr("Regulatory"), tr("VIEW"), callback=self._on_regulatory, enabled=ui_state.is_offroad),
button_item("Change Language", "CHANGE", callback=self._show_language_selection, enabled=ui_state.is_offroad), # TODO: implement multilang
dual_button_item("Reboot", "Power Off", left_callback=self._reboot_prompt, right_callback=self._power_off_prompt), # button_item(tr("Change Language"), tr("CHANGE"), callback=self._show_language_selection, enabled=ui_state.is_offroad),
self._power_off_btn,
] ]
regulatory_btn.set_visible(TICI) regulatory_btn.set_visible(TICI)
return items return items
def _offroad_transition(self):
self._power_off_btn.action_item.right_button.set_visible(ui_state.is_offroad())
def show_event(self):
self._scroller.show_event()
def _render(self, rect): def _render(self, rect):
self._scroller.render(rect) self._scroller.render(rect)
@ -90,34 +107,80 @@ class DeviceLayout(Widget):
def _reset_calibration_prompt(self): def _reset_calibration_prompt(self):
if ui_state.engaged: if ui_state.engaged:
gui_app.set_modal_overlay(lambda: alert_dialog("Disengage to Reset Calibration")) gui_app.set_modal_overlay(alert_dialog(tr("Disengage to Reset Calibration")))
return
gui_app.set_modal_overlay(
lambda: confirm_dialog("Are you sure you want to reset calibration?", "Reset"),
callback=self._reset_calibration,
)
def _reset_calibration(self, result: int):
if ui_state.engaged or result != DialogResult.CONFIRM:
return return
self._params.remove("CalibrationParams") def reset_calibration(result: int):
self._params.remove("LiveTorqueParameters") # Check engaged again in case it changed while the dialog was open
self._params.remove("LiveParameters") if ui_state.engaged or result != DialogResult.CONFIRM:
self._params.remove("LiveParametersV2") return
self._params.remove("LiveDelay")
self._params.put_bool("OnroadCycleRequested", True) self._params.remove("CalibrationParams")
self._params.remove("LiveTorqueParameters")
self._params.remove("LiveParameters")
self._params.remove("LiveParametersV2")
self._params.remove("LiveDelay")
self._params.put_bool("OnroadCycleRequested", True)
self._update_calib_description()
dialog = ConfirmDialog(tr("Are you sure you want to reset calibration?"), tr("Reset"))
gui_app.set_modal_overlay(dialog, callback=reset_calibration)
def _update_calib_description(self):
desc = DESCRIPTIONS['reset_calibration']
calib_bytes = self._params.get("CalibrationParams")
if calib_bytes:
try:
calib = messaging.log_from_bytes(calib_bytes, log.Event).liveCalibration
if calib.calStatus != log.LiveCalibrationData.Status.uncalibrated:
pitch = math.degrees(calib.rpyCalib[1])
yaw = math.degrees(calib.rpyCalib[2])
desc += tr(" Your device is pointed {:.1f}° {} and {:.1f}° {}.").format(abs(pitch), tr("down") if pitch > 0 else tr("up"),
abs(yaw), tr("left") if yaw > 0 else tr("right"))
except Exception:
cloudlog.exception("invalid CalibrationParams")
lag_perc = 0
lag_bytes = self._params.get("LiveDelay")
if lag_bytes:
try:
lag_perc = messaging.log_from_bytes(lag_bytes, log.Event).liveDelay.calPerc
except Exception:
cloudlog.exception("invalid LiveDelay")
if lag_perc < 100:
desc += tr("<br><br>Steering lag calibration is {}% complete.").format(lag_perc)
else:
desc += tr("<br><br>Steering lag calibration is complete.")
torque_bytes = self._params.get("LiveTorqueParameters")
if torque_bytes:
try:
torque = messaging.log_from_bytes(torque_bytes, log.Event).liveTorqueParameters
# don't add for non-torque cars
if torque.useParams:
torque_perc = torque.calPerc
if torque_perc < 100:
desc += tr(" Steering torque response calibration is {}% complete.").format(torque_perc)
else:
desc += tr(" Steering torque response calibration is complete.")
except Exception:
cloudlog.exception("invalid LiveTorqueParameters")
desc += "<br><br>"
desc += tr("openpilot is continuously calibrating, resetting is rarely required. " +
"Resetting calibration will restart openpilot if the car is powered on.")
self._reset_calib_btn.set_description(desc)
def _reboot_prompt(self): def _reboot_prompt(self):
if ui_state.engaged: if ui_state.engaged:
gui_app.set_modal_overlay(lambda: alert_dialog("Disengage to Reboot")) gui_app.set_modal_overlay(alert_dialog(tr("Disengage to Reboot")))
return return
gui_app.set_modal_overlay( dialog = ConfirmDialog(tr("Are you sure you want to reboot?"), tr("Reboot"))
lambda: confirm_dialog("Are you sure you want to reboot?", "Reboot"), gui_app.set_modal_overlay(dialog, callback=self._perform_reboot)
callback=self._perform_reboot,
)
def _perform_reboot(self, result: int): def _perform_reboot(self, result: int):
if not ui_state.engaged and result == DialogResult.CONFIRM: if not ui_state.engaged and result == DialogResult.CONFIRM:
@ -125,13 +188,11 @@ class DeviceLayout(Widget):
def _power_off_prompt(self): def _power_off_prompt(self):
if ui_state.engaged: if ui_state.engaged:
gui_app.set_modal_overlay(lambda: alert_dialog("Disengage to Power Off")) gui_app.set_modal_overlay(alert_dialog(tr("Disengage to Power Off")))
return return
gui_app.set_modal_overlay( dialog = ConfirmDialog(tr("Are you sure you want to power off?"), tr("Power Off"))
lambda: confirm_dialog("Are you sure you want to power off?", "Power Off"), gui_app.set_modal_overlay(dialog, callback=self._perform_power_off)
callback=self._perform_power_off,
)
def _perform_power_off(self, result: int): def _perform_power_off(self, result: int):
if not ui_state.engaged and result == DialogResult.CONFIRM: if not ui_state.engaged and result == DialogResult.CONFIRM:
@ -144,10 +205,13 @@ class DeviceLayout(Widget):
def _on_regulatory(self): def _on_regulatory(self):
if not self._fcc_dialog: if not self._fcc_dialog:
self._fcc_dialog = HtmlRenderer(os.path.join(BASEDIR, "selfdrive/assets/offroad/fcc.html")) self._fcc_dialog = HtmlModal(os.path.join(BASEDIR, "selfdrive/assets/offroad/fcc.html"))
gui_app.set_modal_overlay(self._fcc_dialog)
gui_app.set_modal_overlay(self._fcc_dialog, def _on_review_training_guide(self):
callback=lambda result: setattr(self, '_fcc_dialog', None), if not self._training_guide:
) def completed_callback():
gui_app.set_modal_overlay(None)
def _on_review_training_guide(self): pass self._training_guide = TrainingGuide(completed_callback=completed_callback)
gui_app.set_modal_overlay(self._training_guide)

@ -7,21 +7,23 @@ from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE
from openpilot.system.ui.lib.multilang import tr, trn
from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel
from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.wrap_text import wrap_text
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.selfdrive.ui.lib.api_helpers import get_token from openpilot.selfdrive.ui.lib.api_helpers import get_token
TITLE = "Firehose Mode" TITLE = tr("Firehose Mode")
DESCRIPTION = ( DESCRIPTION = tr(
"openpilot learns to drive by watching humans, like you, drive.\n\n" "openpilot learns to drive by watching humans, like you, drive.\n\n"
+ "Firehose Mode allows you to maximize your training data uploads to improve " + "Firehose 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." + "openpilot's driving models. More data means bigger models, which means better Experimental Mode."
) )
INSTRUCTIONS = ( INSTRUCTIONS = tr(
"For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.\n\n" "For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.\n\n"
+ "Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.\n\n" + "Firehose Mode can also work while you're driving if connected to a hotspot or unlimited SIM card.\n\n\n"
+ "Frequently Asked Questions\n\n" + "Frequently Asked Questions\n\n"
+ "Does it matter how or where I drive? Nope, just drive as you normally would.\n\n" + "Does it matter how or where I drive? Nope, just drive as you normally would.\n\n"
+ "Do all of my segments get pulled in Firehose Mode? No, we selectively pull a subset of your segments.\n\n" + "Do all of my segments get pulled in Firehose Mode? No, we selectively pull a subset of your segments.\n\n"
@ -43,12 +45,16 @@ class FirehoseLayout(Widget):
self.params = Params() self.params = Params()
self.segment_count = self._get_segment_count() self.segment_count = self._get_segment_count()
self.scroll_panel = GuiScrollPanel() self.scroll_panel = GuiScrollPanel()
self._content_height = 0
self.running = True self.running = True
self.update_thread = threading.Thread(target=self._update_loop, daemon=True) self.update_thread = threading.Thread(target=self._update_loop, daemon=True)
self.update_thread.start() self.update_thread.start()
self.last_update_time = 0 self.last_update_time = 0
def show_event(self):
self.scroll_panel.set_offset(0)
def _get_segment_count(self) -> int: def _get_segment_count(self) -> int:
stats = self.params.get(self.PARAM_KEY) stats = self.params.get(self.PARAM_KEY)
if not stats: if not stats:
@ -66,97 +72,71 @@ class FirehoseLayout(Widget):
def _render(self, rect: rl.Rectangle): def _render(self, rect: rl.Rectangle):
# Calculate content dimensions # Calculate content dimensions
content_width = rect.width - 80 content_rect = rl.Rectangle(rect.x, rect.y, rect.width, self._content_height)
content_height = self._calculate_content_height(int(content_width))
content_rect = rl.Rectangle(rect.x, rect.y, rect.width, content_height)
# Handle scrolling and render with clipping # Handle scrolling and render with clipping
scroll_offset = self.scroll_panel.handle_scroll(rect, content_rect) scroll_offset = self.scroll_panel.update(rect, content_rect)
rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height)) rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height))
self._render_content(rect, scroll_offset) self._content_height = self._render_content(rect, scroll_offset)
rl.end_scissor_mode() rl.end_scissor_mode()
def _calculate_content_height(self, content_width: int) -> int: def _render_content(self, rect: rl.Rectangle, scroll_offset: float) -> int:
height = 80 # Top margin
# Title
height += 100 + 40
# Description
desc_font = gui_app.font(FontWeight.NORMAL)
desc_lines = wrap_text(desc_font, DESCRIPTION, 45, content_width)
height += len(desc_lines) * 45 + 40
# Status section
height += 32 # Separator
status_text, _ = self._get_status()
status_lines = wrap_text(gui_app.font(FontWeight.BOLD), status_text, 60, content_width)
height += len(status_lines) * 60 + 20
# Contribution count (if available)
if self.segment_count > 0:
contrib_text = f"{self.segment_count} segment(s) of your driving is in the training dataset so far."
contrib_lines = wrap_text(gui_app.font(FontWeight.BOLD), contrib_text, 52, content_width)
height += len(contrib_lines) * 52 + 20
# Instructions section
height += 32 # Separator
inst_lines = wrap_text(gui_app.font(FontWeight.NORMAL), INSTRUCTIONS, 40, content_width)
height += len(inst_lines) * 40 + 40 # Bottom margin
return height
def _render_content(self, rect: rl.Rectangle, scroll_offset: rl.Vector2):
x = int(rect.x + 40) x = int(rect.x + 40)
y = int(rect.y + 40 + scroll_offset.y) y = int(rect.y + 40 + scroll_offset)
w = int(rect.width - 80) w = int(rect.width - 80)
# Title # Title (centered)
title_font = gui_app.font(FontWeight.MEDIUM) title_font = gui_app.font(FontWeight.MEDIUM)
rl.draw_text_ex(title_font, TITLE, rl.Vector2(x, y), 100, 0, rl.WHITE) text_width = measure_text_cached(title_font, TITLE, 100).x
y += 140 title_x = rect.x + (rect.width - text_width) / 2
rl.draw_text_ex(title_font, TITLE, rl.Vector2(title_x, y), 100, 0, rl.WHITE)
y += 200
# Description # Description
y = self._draw_wrapped_text(x, y, w, DESCRIPTION, gui_app.font(FontWeight.NORMAL), 45, rl.WHITE) y = self._draw_wrapped_text(x, y, w, DESCRIPTION, gui_app.font(FontWeight.NORMAL), 45, rl.WHITE)
y += 40 y += 40 + 20
# Separator # Separator
rl.draw_rectangle(x, y, w, 2, self.GRAY) rl.draw_rectangle(x, y, w, 2, self.GRAY)
y += 30 y += 30 + 20
# Status # Status
status_text, status_color = self._get_status() status_text, status_color = self._get_status()
y = self._draw_wrapped_text(x, y, w, status_text, gui_app.font(FontWeight.BOLD), 60, status_color) y = self._draw_wrapped_text(x, y, w, status_text, gui_app.font(FontWeight.BOLD), 60, status_color)
y += 20 y += 20 + 20
# Contribution count (if available) # Contribution count (if available)
if self.segment_count > 0: if self.segment_count > 0:
contrib_text = f"{self.segment_count} segment(s) of your driving is in the training dataset so far." contrib_text = trn("{} segment of your driving is in the training dataset so far.",
"{} segments of your driving is in the training dataset so far.", self.segment_count).format(self.segment_count)
y = self._draw_wrapped_text(x, y, w, contrib_text, gui_app.font(FontWeight.BOLD), 52, rl.WHITE) y = self._draw_wrapped_text(x, y, w, contrib_text, gui_app.font(FontWeight.BOLD), 52, rl.WHITE)
y += 20 y += 20 + 20
# Separator # Separator
rl.draw_rectangle(x, y, w, 2, self.GRAY) rl.draw_rectangle(x, y, w, 2, self.GRAY)
y += 30 y += 30 + 20
# Instructions # Instructions
self._draw_wrapped_text(x, y, w, INSTRUCTIONS, gui_app.font(FontWeight.NORMAL), 40, self.LIGHT_GRAY) y = self._draw_wrapped_text(x, y, w, INSTRUCTIONS, gui_app.font(FontWeight.NORMAL), 40, self.LIGHT_GRAY)
# bottom margin + remove effect of scroll offset
return int(round(y - self.scroll_panel.offset + 40))
def _draw_wrapped_text(self, x, y, width, text, font, size, color): def _draw_wrapped_text(self, x, y, width, text, font, font_size, color):
wrapped = wrap_text(font, text, size, width) wrapped = wrap_text(font, text, font_size, width)
for line in wrapped: for line in wrapped:
rl.draw_text_ex(font, line, rl.Vector2(x, y), size, 0, color) rl.draw_text_ex(font, line, rl.Vector2(x, y), font_size, 0, color)
y += size y += font_size * FONT_SCALE
return y return round(y)
def _get_status(self) -> tuple[str, rl.Color]: def _get_status(self) -> tuple[str, rl.Color]:
network_type = ui_state.sm["deviceState"].networkType network_type = ui_state.sm["deviceState"].networkType
network_metered = ui_state.sm["deviceState"].networkMetered network_metered = ui_state.sm["deviceState"].networkMetered
if not network_metered and network_type != 0: # Not metered and connected if not network_metered and network_type != 0: # Not metered and connected
return "ACTIVE", self.GREEN return tr("ACTIVE"), self.GREEN
else: else:
return "INACTIVE: connect to an unmetered network", self.RED return tr("INACTIVE: connect to an unmetered network"), self.RED
def _fetch_firehose_stats(self): def _fetch_firehose_stats(self):
try: try:

@ -8,6 +8,7 @@ from openpilot.selfdrive.ui.layouts.settings.firehose import FirehoseLayout
from openpilot.selfdrive.ui.layouts.settings.software import SoftwareLayout from openpilot.selfdrive.ui.layouts.settings.software import SoftwareLayout
from openpilot.selfdrive.ui.layouts.settings.toggles import TogglesLayout from openpilot.selfdrive.ui.layouts.settings.toggles import TogglesLayout
from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.lib.wifi_manager import WifiManager from openpilot.system.ui.lib.wifi_manager import WifiManager
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
@ -58,12 +59,12 @@ class SettingsLayout(Widget):
wifi_manager.set_active(False) wifi_manager.set_active(False)
self._panels = { self._panels = {
PanelType.DEVICE: PanelInfo("Device", DeviceLayout()), PanelType.DEVICE: PanelInfo(tr("Device"), DeviceLayout()),
PanelType.NETWORK: PanelInfo("Network", NetworkUI(wifi_manager)), PanelType.NETWORK: PanelInfo(tr("Network"), NetworkUI(wifi_manager)),
PanelType.TOGGLES: PanelInfo("Toggles", TogglesLayout()), PanelType.TOGGLES: PanelInfo(tr("Toggles"), TogglesLayout()),
PanelType.SOFTWARE: PanelInfo("Software", SoftwareLayout()), PanelType.SOFTWARE: PanelInfo(tr("Software"), SoftwareLayout()),
PanelType.FIREHOSE: PanelInfo("Firehose", FirehoseLayout()), PanelType.FIREHOSE: PanelInfo(tr("Firehose"), FirehoseLayout()),
PanelType.DEVELOPER: PanelInfo("Developer", DeveloperLayout()), PanelType.DEVELOPER: PanelInfo(tr("Developer"), DeveloperLayout()),
} }
self._font_medium = gui_app.font(FontWeight.MEDIUM) self._font_medium = gui_app.font(FontWeight.MEDIUM)

@ -1,42 +1,166 @@
from openpilot.common.params import Params import os
import time
import datetime
from openpilot.common.time_helpers import system_time_valid
from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.multilang import tr, trn
from openpilot.system.ui.widgets import Widget, DialogResult from openpilot.system.ui.widgets import Widget, DialogResult
from openpilot.system.ui.widgets.confirm_dialog import confirm_dialog from openpilot.system.ui.widgets.confirm_dialog import ConfirmDialog
from openpilot.system.ui.widgets.list_view import button_item, text_item from openpilot.system.ui.widgets.list_view import button_item, text_item, ListItem
from openpilot.system.ui.widgets.scroller import Scroller from openpilot.system.ui.widgets.scroller import Scroller
# TODO: remove this. updater fails to respond on startup if time is not correct
UPDATED_TIMEOUT = 10 # seconds to wait for updated to respond
def time_ago(date: datetime.datetime | None) -> str:
if not date:
return tr("never")
if not system_time_valid():
return date.strftime("%a %b %d %Y")
now = datetime.datetime.now(datetime.UTC)
if date.tzinfo is None:
date = date.replace(tzinfo=datetime.UTC)
diff_seconds = int((now - date).total_seconds())
if diff_seconds < 60:
return tr("now")
if diff_seconds < 3600:
m = diff_seconds // 60
return trn("{} minute ago", "{} minutes ago", m).format(m)
if diff_seconds < 86400:
h = diff_seconds // 3600
return trn("{} hour ago", "{} hours ago", h).format(h)
if diff_seconds < 604800:
d = diff_seconds // 86400
return trn("{} day ago", "{} days ago", d).format(d)
return date.strftime("%a %b %d %Y")
class SoftwareLayout(Widget): class SoftwareLayout(Widget):
def __init__(self): def __init__(self):
super().__init__() super().__init__()
self._params = Params() self._onroad_label = ListItem(title=tr("Updates are only downloaded while the car is off."))
self._version_item = text_item(tr("Current Version"), ui_state.params.get("UpdaterCurrentDescription") or "")
self._download_btn = button_item(tr("Download"), tr("CHECK"), callback=self._on_download_update)
# Install button is initially hidden
self._install_btn = button_item(tr("Install Update"), tr("INSTALL"), callback=self._on_install_update)
self._install_btn.set_visible(False)
# Track waiting-for-updater transition to avoid brief re-enable while still idle
self._waiting_for_updater = False
self._waiting_start_ts: float = 0.0
items = self._init_items() items = self._init_items()
self._scroller = Scroller(items, line_separator=True, spacing=0) self._scroller = Scroller(items, line_separator=True, spacing=0)
def _init_items(self): def _init_items(self):
items = [ items = [
text_item("Current Version", ""), self._onroad_label,
button_item("Download", "CHECK", callback=self._on_download_update), self._version_item,
button_item("Install Update", "INSTALL", callback=self._on_install_update), self._download_btn,
button_item("Target Branch", "SELECT", callback=self._on_select_branch), self._install_btn,
button_item("Uninstall", "UNINSTALL", callback=self._on_uninstall), # TODO: implement branch switching
# button_item("Target Branch", "SELECT", callback=self._on_select_branch),
button_item("Uninstall", tr("UNINSTALL"), callback=self._on_uninstall),
] ]
return items return items
def show_event(self):
self._scroller.show_event()
def _render(self, rect): def _render(self, rect):
self._scroller.render(rect) self._scroller.render(rect)
def _on_download_update(self): pass def _update_state(self):
def _on_install_update(self): pass # Show/hide onroad warning
def _on_select_branch(self): pass self._onroad_label.set_visible(ui_state.is_onroad())
# Update current version and release notes
current_desc = ui_state.params.get("UpdaterCurrentDescription") or ""
current_release_notes = (ui_state.params.get("UpdaterCurrentReleaseNotes") or b"").decode("utf-8", "replace")
self._version_item.action_item.set_text(current_desc)
self._version_item.set_description(current_release_notes)
# Update download button visibility and state
self._download_btn.set_visible(ui_state.is_offroad())
updater_state = ui_state.params.get("UpdaterState") or "idle"
failed_count = ui_state.params.get("UpdateFailedCount") or 0
fetch_available = ui_state.params.get_bool("UpdaterFetchAvailable")
update_available = ui_state.params.get_bool("UpdateAvailable")
if updater_state != "idle":
# Updater responded
self._waiting_for_updater = False
self._download_btn.action_item.set_enabled(False)
self._download_btn.action_item.set_value(updater_state)
else:
if failed_count > 0:
self._download_btn.action_item.set_value(tr("failed to check for update"))
self._download_btn.action_item.set_text(tr("CHECK"))
elif fetch_available:
self._download_btn.action_item.set_value(tr("update available"))
self._download_btn.action_item.set_text(tr("DOWNLOAD"))
else:
last_update = ui_state.params.get("LastUpdateTime")
if last_update:
formatted = time_ago(last_update)
self._download_btn.action_item.set_value(tr("up to date, last checked {}").format(formatted))
else:
self._download_btn.action_item.set_value(tr("up to date, last checked never"))
self._download_btn.action_item.set_text(tr("CHECK"))
# If we've been waiting too long without a state change, reset state
if self._waiting_for_updater and (time.monotonic() - self._waiting_start_ts > UPDATED_TIMEOUT):
self._waiting_for_updater = False
# Only enable if we're not waiting for updater to flip out of idle
self._download_btn.action_item.set_enabled(not self._waiting_for_updater)
# Update install button
self._install_btn.set_visible(ui_state.is_offroad() and update_available)
if update_available:
new_desc = ui_state.params.get("UpdaterNewDescription") or ""
new_release_notes = (ui_state.params.get("UpdaterNewReleaseNotes") or b"").decode("utf-8", "replace")
self._install_btn.action_item.set_text(tr("INSTALL"))
self._install_btn.action_item.set_value(new_desc)
self._install_btn.set_description(new_release_notes)
# Enable install button for testing (like Qt showEvent)
self._install_btn.action_item.set_enabled(True)
else:
self._install_btn.set_visible(False)
def _on_download_update(self):
# Check if we should start checking or start downloading
self._download_btn.action_item.set_enabled(False)
if self._download_btn.action_item.text == tr("CHECK"):
# Start checking for updates
self._waiting_for_updater = True
self._waiting_start_ts = time.monotonic()
os.system("pkill -SIGUSR1 -f system.updated.updated")
else:
# Start downloading
self._waiting_for_updater = True
self._waiting_start_ts = time.monotonic()
os.system("pkill -SIGHUP -f system.updated.updated")
def _on_uninstall(self): def _on_uninstall(self):
def handle_uninstall_confirmation(result): def handle_uninstall_confirmation(result):
if result == DialogResult.CONFIRM: if result == DialogResult.CONFIRM:
self._params.put_bool("DoUninstall", True) ui_state.params.put_bool("DoUninstall", True)
dialog = ConfirmDialog(tr("Are you sure you want to uninstall?"), tr("Uninstall"))
gui_app.set_modal_overlay(dialog, callback=handle_uninstall_confirmation)
gui_app.set_modal_overlay( def _on_install_update(self):
lambda: confirm_dialog("Are you sure you want to uninstall?", "Uninstall"), # Trigger reboot to install update
callback=handle_uninstall_confirmation, self._install_btn.action_item.set_enabled(False)
) ui_state.params.put_bool("DoReboot", True)
def _on_select_branch(self): pass

@ -1,28 +1,36 @@
from openpilot.common.params import Params from cereal import log
from openpilot.common.params import Params, UnknownKeyName
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.list_view import multiple_button_item, toggle_item from openpilot.system.ui.widgets.list_view import multiple_button_item, toggle_item
from openpilot.system.ui.widgets.scroller import Scroller from openpilot.system.ui.widgets.scroller import Scroller
from openpilot.system.ui.widgets.confirm_dialog import ConfirmDialog
from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.widgets import DialogResult
from openpilot.selfdrive.ui.ui_state import ui_state
PERSONALITY_TO_INT = log.LongitudinalPersonality.schema.enumerants
# Description constants # Description constants
DESCRIPTIONS = { DESCRIPTIONS = {
"OpenpilotEnabledToggle": ( "OpenpilotEnabledToggle": tr(
"Use the openpilot system for adaptive cruise control and lane keep driver assistance. " + "Use the openpilot system for adaptive cruise control and lane keep driver assistance. " +
"Your attention is required at all times to use this feature." "Your attention is required at all times to use this feature."
), ),
"DisengageOnAccelerator": "When enabled, pressing the accelerator pedal will disengage openpilot.", "DisengageOnAccelerator": tr("When enabled, pressing the accelerator pedal will disengage openpilot."),
"LongitudinalPersonality": ( "LongitudinalPersonality": tr(
"Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. " + "Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. " +
"In relaxed mode openpilot will stay further away from lead cars. On supported cars, you can cycle through these personalities with " + "In relaxed mode openpilot will stay further away from lead cars. On supported cars, you can cycle through these personalities with " +
"your steering wheel distance button." "your steering wheel distance button."
), ),
"IsLdwEnabled": ( "IsLdwEnabled": tr(
"Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line " + "Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line " +
"without a turn signal activated while driving over 31 mph (50 km/h)." "without a turn signal activated while driving over 31 mph (50 km/h)."
), ),
"AlwaysOnDM": "Enable driver monitoring even when openpilot is not engaged.", "AlwaysOnDM": tr("Enable driver monitoring even when openpilot is not engaged."),
'RecordFront': "Upload data from the driver facing camera and help improve the driver monitoring algorithm.", 'RecordFront': tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."),
"IsMetric": "Display speed in km/h instead of mph.", "IsMetric": tr("Display speed in km/h instead of mph."),
"RecordAudio": "Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect.", "RecordAudio": tr("Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect."),
} }
@ -30,66 +38,204 @@ class TogglesLayout(Widget):
def __init__(self): def __init__(self):
super().__init__() super().__init__()
self._params = Params() self._params = Params()
items = [ self._is_release = self._params.get_bool("IsReleaseBranch")
toggle_item(
"Enable openpilot", # param, title, desc, icon, needs_restart
self._toggle_defs = {
"OpenpilotEnabledToggle": (
tr("Enable openpilot"),
DESCRIPTIONS["OpenpilotEnabledToggle"], DESCRIPTIONS["OpenpilotEnabledToggle"],
self._params.get_bool("OpenpilotEnabledToggle"), "chffr_wheel.png",
icon="chffr_wheel.png", True,
), ),
toggle_item( "ExperimentalMode": (
"Experimental Mode", tr("Experimental Mode"),
initial_state=self._params.get_bool("ExperimentalMode"), "",
icon="experimental_white.png", "experimental_white.png",
False,
), ),
toggle_item( "DisengageOnAccelerator": (
"Disengage on Accelerator Pedal", tr("Disengage on Accelerator Pedal"),
DESCRIPTIONS["DisengageOnAccelerator"], DESCRIPTIONS["DisengageOnAccelerator"],
self._params.get_bool("DisengageOnAccelerator"), "disengage_on_accelerator.png",
icon="disengage_on_accelerator.png", False,
), ),
multiple_button_item( "IsLdwEnabled": (
"Driving Personality", tr("Enable Lane Departure Warnings"),
DESCRIPTIONS["LongitudinalPersonality"],
buttons=["Aggressive", "Standard", "Relaxed"],
button_width=255,
callback=self._set_longitudinal_personality,
selected_index=self._params.get("LongitudinalPersonality", return_default=True),
icon="speed_limit.png"
),
toggle_item(
"Enable Lane Departure Warnings",
DESCRIPTIONS["IsLdwEnabled"], DESCRIPTIONS["IsLdwEnabled"],
self._params.get_bool("IsLdwEnabled"), "warning.png",
icon="warning.png", False,
), ),
toggle_item( "AlwaysOnDM": (
"Always-On Driver Monitoring", tr("Always-On Driver Monitoring"),
DESCRIPTIONS["AlwaysOnDM"], DESCRIPTIONS["AlwaysOnDM"],
self._params.get_bool("AlwaysOnDM"), "monitoring.png",
icon="monitoring.png", False,
), ),
toggle_item( "RecordFront": (
"Record and Upload Driver Camera", tr("Record and Upload Driver Camera"),
DESCRIPTIONS["RecordFront"], DESCRIPTIONS["RecordFront"],
self._params.get_bool("RecordFront"), "monitoring.png",
icon="monitoring.png", True,
), ),
toggle_item( "RecordAudio": (
"Record Microphone Audio", tr("Record and Upload Microphone Audio"),
DESCRIPTIONS["RecordAudio"], DESCRIPTIONS["RecordAudio"],
self._params.get_bool("RecordAudio"), "microphone.png",
icon="microphone.png", True,
), ),
toggle_item( "IsMetric": (
"Use Metric System", DESCRIPTIONS["IsMetric"], self._params.get_bool("IsMetric"), icon="metric.png" tr("Use Metric System"),
DESCRIPTIONS["IsMetric"],
"metric.png",
False,
), ),
] }
self._long_personality_setting = multiple_button_item(
tr("Driving Personality"),
DESCRIPTIONS["LongitudinalPersonality"],
buttons=[tr("Aggressive"), tr("Standard"), tr("Relaxed")],
button_width=255,
callback=self._set_longitudinal_personality,
selected_index=self._params.get("LongitudinalPersonality", return_default=True),
icon="speed_limit.png"
)
self._toggles = {}
self._locked_toggles = set()
for param, (title, desc, icon, needs_restart) in self._toggle_defs.items():
toggle = toggle_item(
title,
desc,
self._params.get_bool(param),
callback=lambda state, p=param: self._toggle_callback(state, p),
icon=icon,
)
try:
locked = self._params.get_bool(param + "Lock")
except UnknownKeyName:
locked = False
toggle.action_item.set_enabled(not locked)
if needs_restart and not locked:
toggle.set_description(toggle.description + tr(" Changing this setting will restart openpilot if the car is powered on."))
# track for engaged state updates
if locked:
self._locked_toggles.add(param)
self._toggles[param] = toggle
# insert longitudinal personality after NDOG toggle
if param == "DisengageOnAccelerator":
self._toggles["LongitudinalPersonality"] = self._long_personality_setting
self._update_experimental_mode_icon()
self._scroller = Scroller(list(self._toggles.values()), line_separator=True, spacing=0)
ui_state.add_engaged_transition_callback(self._update_toggles)
def _update_state(self):
if ui_state.sm.updated["selfdriveState"]:
personality = PERSONALITY_TO_INT[ui_state.sm["selfdriveState"].personality]
if personality != ui_state.personality and ui_state.started:
self._long_personality_setting.action_item.set_selected_button(personality)
ui_state.personality = personality
def show_event(self):
self._scroller.show_event()
self._update_toggles()
self._scroller = Scroller(items, line_separator=True, spacing=0) def _update_toggles(self):
ui_state.update_params()
e2e_description = tr(
"openpilot defaults to driving in chill mode. Experimental mode enables alpha-level features that aren't ready for chill mode. " +
"Experimental features are listed below:<br>" +
"<h4>End-to-End Longitudinal Control</h4><br>" +
"Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. " +
"Since the driving model decides the speed to drive, the set speed will only act as an upper bound. This is an alpha quality feature; " +
"mistakes should be expected.<br>" +
"<h4>New Driving Visualization</h4><br>" +
"The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. " +
"The Experimental mode logo will also be shown in the top right corner."
)
if ui_state.CP is not None:
if ui_state.has_longitudinal_control:
self._toggles["ExperimentalMode"].action_item.set_enabled(True)
self._toggles["ExperimentalMode"].set_description(e2e_description)
self._long_personality_setting.action_item.set_enabled(True)
else:
# no long for now
self._toggles["ExperimentalMode"].action_item.set_enabled(False)
self._toggles["ExperimentalMode"].action_item.set_state(False)
self._long_personality_setting.action_item.set_enabled(False)
self._params.remove("ExperimentalMode")
unavailable = tr("Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.")
long_desc = unavailable + " " + tr("openpilot longitudinal control may come in a future update.")
if ui_state.CP.alphaLongitudinalAvailable:
if self._is_release:
long_desc = unavailable + " " + tr("An alpha version of openpilot longitudinal control can be tested, along with " +
"Experimental mode, on non-release branches.")
else:
long_desc = tr("Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode.")
self._toggles["ExperimentalMode"].set_description("<b>" + long_desc + "</b><br><br>" + e2e_description)
else:
self._toggles["ExperimentalMode"].set_description(e2e_description)
self._update_experimental_mode_icon()
# TODO: make a param control list item so we don't need to manage internal state as much here
# refresh toggles from params to mirror external changes
for param in self._toggle_defs:
self._toggles[param].action_item.set_state(self._params.get_bool(param))
# these toggles need restart, block while engaged
for toggle_def in self._toggle_defs:
if self._toggle_defs[toggle_def][3] and toggle_def not in self._locked_toggles:
self._toggles[toggle_def].action_item.set_enabled(not ui_state.engaged)
def _render(self, rect): def _render(self, rect):
self._scroller.render(rect) self._scroller.render(rect)
def _update_experimental_mode_icon(self):
icon = "experimental.png" if self._toggles["ExperimentalMode"].action_item.get_state() else "experimental_white.png"
self._toggles["ExperimentalMode"].set_icon(icon)
def _handle_experimental_mode_toggle(self, state: bool):
confirmed = self._params.get_bool("ExperimentalModeConfirmed")
if state and not confirmed:
def confirm_callback(result: int):
if result == DialogResult.CONFIRM:
self._params.put_bool("ExperimentalMode", True)
self._params.put_bool("ExperimentalModeConfirmed", True)
else:
self._toggles["ExperimentalMode"].action_item.set_state(False)
self._update_experimental_mode_icon()
# show confirmation dialog
content = (f"<h1>{self._toggles['ExperimentalMode'].title}</h1><br>" +
f"<p>{self._toggles['ExperimentalMode'].description}</p>")
dlg = ConfirmDialog(content, tr("Enable"), rich=True)
gui_app.set_modal_overlay(dlg, callback=confirm_callback)
else:
self._update_experimental_mode_icon()
self._params.put_bool("ExperimentalMode", state)
def _toggle_callback(self, state: bool, param: str):
if param == "ExperimentalMode":
self._handle_experimental_mode_toggle(state)
return
self._params.put_bool(param, state)
if self._toggle_defs[param][3]:
self._params.put_bool("OnroadCycleRequested", True)
def _set_longitudinal_personality(self, button_index: int): def _set_longitudinal_personality(self, button_index: int):
self._params.put("LongitudinalPersonality", button_index) self._params.put("LongitudinalPersonality", button_index)

@ -4,7 +4,8 @@ from dataclasses import dataclass
from collections.abc import Callable from collections.abc import Callable
from cereal import log from cereal import log
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos, FONT_SCALE
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
@ -23,7 +24,6 @@ NetworkType = log.DeviceState.NetworkType
# Color scheme # Color scheme
class Colors: class Colors:
SIDEBAR_BG = rl.Color(57, 57, 57, 255)
WHITE = rl.WHITE WHITE = rl.WHITE
WHITE_DIM = rl.Color(255, 255, 255, 85) WHITE_DIM = rl.Color(255, 255, 255, 85)
GRAY = rl.Color(84, 84, 84, 255) GRAY = rl.Color(84, 84, 84, 255)
@ -40,13 +40,13 @@ class Colors:
NETWORK_TYPES = { NETWORK_TYPES = {
NetworkType.none: "Offline", NetworkType.none: tr("--"),
NetworkType.wifi: "WiFi", NetworkType.wifi: tr("Wi-Fi"),
NetworkType.cell2G: "2G", NetworkType.ethernet: tr("ETH"),
NetworkType.cell3G: "3G", NetworkType.cell2G: tr("2G"),
NetworkType.cell4G: "LTE", NetworkType.cell3G: tr("3G"),
NetworkType.cell5G: "5G", NetworkType.cell4G: tr("LTE"),
NetworkType.ethernet: "Ethernet", NetworkType.cell5G: tr("5G"),
} }
@ -68,27 +68,33 @@ class Sidebar(Widget):
self._net_type = NETWORK_TYPES.get(NetworkType.none) self._net_type = NETWORK_TYPES.get(NetworkType.none)
self._net_strength = 0 self._net_strength = 0
self._temp_status = MetricData("TEMP", "GOOD", Colors.GOOD) self._temp_status = MetricData(tr("TEMP"), tr("GOOD"), Colors.GOOD)
self._panda_status = MetricData("VEHICLE", "ONLINE", Colors.GOOD) self._panda_status = MetricData(tr("VEHICLE"), tr("ONLINE"), Colors.GOOD)
self._connect_status = MetricData("CONNECT", "OFFLINE", Colors.WARNING) self._connect_status = MetricData(tr("CONNECT"), tr("OFFLINE"), Colors.WARNING)
self._recording_audio = False
self._home_img = gui_app.texture("images/button_home.png", HOME_BTN.width, HOME_BTN.height) self._home_img = gui_app.texture("images/button_home.png", HOME_BTN.width, HOME_BTN.height)
self._flag_img = gui_app.texture("images/button_flag.png", HOME_BTN.width, HOME_BTN.height) self._flag_img = gui_app.texture("images/button_flag.png", HOME_BTN.width, HOME_BTN.height)
self._settings_img = gui_app.texture("images/button_settings.png", SETTINGS_BTN.width, SETTINGS_BTN.height) self._settings_img = gui_app.texture("images/button_settings.png", SETTINGS_BTN.width, SETTINGS_BTN.height)
self._mic_img = gui_app.texture("icons/microphone.png", 30, 30)
self._mic_indicator_rect = rl.Rectangle(0, 0, 0, 0)
self._font_regular = gui_app.font(FontWeight.NORMAL) self._font_regular = gui_app.font(FontWeight.NORMAL)
self._font_bold = gui_app.font(FontWeight.SEMI_BOLD) self._font_bold = gui_app.font(FontWeight.SEMI_BOLD)
# Callbacks # Callbacks
self._on_settings_click: Callable | None = None self._on_settings_click: Callable | None = None
self._on_flag_click: Callable | None = None self._on_flag_click: Callable | None = None
self._open_settings_callback: Callable | None = None
def set_callbacks(self, on_settings: Callable | None = None, on_flag: Callable | None = None): def set_callbacks(self, on_settings: Callable | None = None, on_flag: Callable | None = None,
open_settings: Callable | None = None):
self._on_settings_click = on_settings self._on_settings_click = on_settings
self._on_flag_click = on_flag self._on_flag_click = on_flag
self._open_settings_callback = open_settings
def _render(self, rect: rl.Rectangle): def _render(self, rect: rl.Rectangle):
# Background # Background
rl.draw_rectangle_rec(rect, Colors.SIDEBAR_BG) rl.draw_rectangle_rec(rect, rl.BLACK)
self._draw_buttons(rect) self._draw_buttons(rect)
self._draw_network_indicator(rect) self._draw_network_indicator(rect)
@ -101,13 +107,14 @@ class Sidebar(Widget):
device_state = sm['deviceState'] device_state = sm['deviceState']
self._recording_audio = ui_state.recording_audio
self._update_network_status(device_state) self._update_network_status(device_state)
self._update_temperature_status(device_state) self._update_temperature_status(device_state)
self._update_connection_status(device_state) self._update_connection_status(device_state)
self._update_panda_status() self._update_panda_status()
def _update_network_status(self, device_state): def _update_network_status(self, device_state):
self._net_type = NETWORK_TYPES.get(device_state.networkType.raw, "Unknown") self._net_type = NETWORK_TYPES.get(device_state.networkType.raw, tr("Unknown"))
strength = device_state.networkStrength strength = device_state.networkStrength
self._net_strength = max(0, min(5, strength.raw + 1)) if strength > 0 else 0 self._net_strength = max(0, min(5, strength.raw + 1)) if strength > 0 else 0
@ -115,26 +122,26 @@ class Sidebar(Widget):
thermal_status = device_state.thermalStatus thermal_status = device_state.thermalStatus
if thermal_status == ThermalStatus.green: if thermal_status == ThermalStatus.green:
self._temp_status.update("TEMP", "GOOD", Colors.GOOD) self._temp_status.update(tr("TEMP"), tr("GOOD"), Colors.GOOD)
elif thermal_status == ThermalStatus.yellow: elif thermal_status == ThermalStatus.yellow:
self._temp_status.update("TEMP", "OK", Colors.WARNING) self._temp_status.update(tr("TEMP"), tr("OK"), Colors.WARNING)
else: else:
self._temp_status.update("TEMP", "HIGH", Colors.DANGER) self._temp_status.update(tr("TEMP"), tr("HIGH"), Colors.DANGER)
def _update_connection_status(self, device_state): def _update_connection_status(self, device_state):
last_ping = device_state.lastAthenaPingTime last_ping = device_state.lastAthenaPingTime
if last_ping == 0: if last_ping == 0:
self._connect_status.update("CONNECT", "OFFLINE", Colors.WARNING) self._connect_status.update(tr("CONNECT"), tr("OFFLINE"), Colors.WARNING)
elif time.monotonic_ns() - last_ping < 80_000_000_000: # 80 seconds in nanoseconds elif time.monotonic_ns() - last_ping < 80_000_000_000: # 80 seconds in nanoseconds
self._connect_status.update("CONNECT", "ONLINE", Colors.GOOD) self._connect_status.update(tr("CONNECT"), tr("ONLINE"), Colors.GOOD)
else: else:
self._connect_status.update("CONNECT", "ERROR", Colors.DANGER) self._connect_status.update(tr("CONNECT"), tr("ERROR"), Colors.DANGER)
def _update_panda_status(self): def _update_panda_status(self):
if ui_state.panda_type == log.PandaState.PandaType.unknown: if ui_state.panda_type == log.PandaState.PandaType.unknown:
self._panda_status.update("NO", "PANDA", Colors.DANGER) self._panda_status.update(tr("NO"), tr("PANDA"), Colors.DANGER)
else: else:
self._panda_status.update("VEHICLE", "ONLINE", Colors.GOOD) self._panda_status.update(tr("VEHICLE"), tr("ONLINE"), Colors.GOOD)
def _handle_mouse_release(self, mouse_pos: MousePos): def _handle_mouse_release(self, mouse_pos: MousePos):
if rl.check_collision_point_rec(mouse_pos, SETTINGS_BTN): if rl.check_collision_point_rec(mouse_pos, SETTINGS_BTN):
@ -143,6 +150,9 @@ class Sidebar(Widget):
elif rl.check_collision_point_rec(mouse_pos, HOME_BTN) and ui_state.started: elif rl.check_collision_point_rec(mouse_pos, HOME_BTN) and ui_state.started:
if self._on_flag_click: if self._on_flag_click:
self._on_flag_click() self._on_flag_click()
elif self._recording_audio and rl.check_collision_point_rec(mouse_pos, self._mic_indicator_rect):
if self._open_settings_callback:
self._open_settings_callback()
def _draw_buttons(self, rect: rl.Rectangle): def _draw_buttons(self, rect: rl.Rectangle):
mouse_pos = rl.get_mouse_position() mouse_pos = rl.get_mouse_position()
@ -160,6 +170,17 @@ class Sidebar(Widget):
tint = Colors.BUTTON_PRESSED if (ui_state.started and flag_pressed) else Colors.BUTTON_NORMAL tint = Colors.BUTTON_PRESSED if (ui_state.started and flag_pressed) else Colors.BUTTON_NORMAL
rl.draw_texture(button_img, int(HOME_BTN.x), int(HOME_BTN.y), tint) rl.draw_texture(button_img, int(HOME_BTN.x), int(HOME_BTN.y), tint)
# Microphone button
if self._recording_audio:
self._mic_indicator_rect = rl.Rectangle(rect.x + rect.width - 130, rect.y + 245, 75, 40)
mic_pressed = mouse_down and rl.check_collision_point_rec(mouse_pos, self._mic_indicator_rect)
bg_color = rl.Color(Colors.DANGER.r, Colors.DANGER.g, Colors.DANGER.b, int(255 * 0.65)) if mic_pressed else Colors.DANGER
rl.draw_rectangle_rounded(self._mic_indicator_rect, 1, 10, bg_color)
rl.draw_texture(self._mic_img, int(self._mic_indicator_rect.x + (self._mic_indicator_rect.width - self._mic_img.width) / 2),
int(self._mic_indicator_rect.y + (self._mic_indicator_rect.height - self._mic_img.height) / 2), Colors.WHITE)
def _draw_network_indicator(self, rect: rl.Rectangle): def _draw_network_indicator(self, rect: rl.Rectangle):
# Signal strength dots # Signal strength dots
x_start = rect.x + 58 x_start = rect.x + 58
@ -197,7 +218,7 @@ class Sidebar(Widget):
# Draw label and value # Draw label and value
labels = [metric.label, metric.value] labels = [metric.label, metric.value]
text_y = metric_rect.y + (metric_rect.height / 2 - len(labels) * FONT_SIZE) text_y = metric_rect.y + (metric_rect.height / 2 - len(labels) * FONT_SIZE * FONT_SCALE)
for text in labels: for text in labels:
text_size = measure_text_cached(self._font_bold, text, FONT_SIZE) text_size = measure_text_cached(self._font_bold, text, FONT_SIZE)
text_y += text_size.y text_y += text_size.y

@ -5,9 +5,10 @@ from cereal import messaging, log
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.hardware import TICI from openpilot.system.hardware import TICI
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.label import gui_text_box from openpilot.system.ui.widgets.label import Label
AlertSize = log.SelfdriveState.AlertSize AlertSize = log.SelfdriveState.AlertSize
AlertStatus = log.SelfdriveState.AlertStatus AlertStatus = log.SelfdriveState.AlertStatus
@ -21,14 +22,19 @@ ALERT_FONT_SMALL = 66
ALERT_FONT_MEDIUM = 74 ALERT_FONT_MEDIUM = 74
ALERT_FONT_BIG = 88 ALERT_FONT_BIG = 88
ALERT_HEIGHTS = {
AlertSize.small: 271,
AlertSize.mid: 420,
}
SELFDRIVE_STATE_TIMEOUT = 5 # Seconds SELFDRIVE_STATE_TIMEOUT = 5 # Seconds
SELFDRIVE_UNRESPONSIVE_TIMEOUT = 10 # Seconds SELFDRIVE_UNRESPONSIVE_TIMEOUT = 10 # Seconds
# Constants # Constants
ALERT_COLORS = { ALERT_COLORS = {
AlertStatus.normal: rl.Color(0, 0, 0, 235), # Black AlertStatus.normal: rl.Color(0x15, 0x15, 0x15, 0xF1), # #151515 with alpha 0xF1
AlertStatus.userPrompt: rl.Color(0xFE, 0x8C, 0x34, 235), # Orange AlertStatus.userPrompt: rl.Color(0xDA, 0x6F, 0x25, 0xF1), # #DA6F25 with alpha 0xF1
AlertStatus.critical: rl.Color(0xC9, 0x22, 0x31, 235), # Red AlertStatus.critical: rl.Color(0xC9, 0x22, 0x31, 0xF1), # #C92231 with alpha 0xF1
} }
@ -42,24 +48,24 @@ class Alert:
# Pre-defined alert instances # Pre-defined alert instances
ALERT_STARTUP_PENDING = Alert( ALERT_STARTUP_PENDING = Alert(
text1="openpilot Unavailable", text1=tr("openpilot Unavailable"),
text2="Waiting to start", text2=tr("Waiting to start"),
size=AlertSize.mid, size=AlertSize.mid,
status=AlertStatus.normal, status=AlertStatus.normal,
) )
ALERT_CRITICAL_TIMEOUT = Alert( ALERT_CRITICAL_TIMEOUT = Alert(
text1="TAKE CONTROL IMMEDIATELY", text1=tr("TAKE CONTROL IMMEDIATELY"),
text2="System Unresponsive", text2=tr("System Unresponsive"),
size=AlertSize.full, size=AlertSize.full,
status=AlertStatus.critical, status=AlertStatus.critical,
) )
ALERT_CRITICAL_REBOOT = Alert( ALERT_CRITICAL_REBOOT = Alert(
text1="System Unresponsive", text1=tr("System Unresponsive"),
text2="Reboot Device", text2=tr("Reboot Device"),
size=AlertSize.full, size=AlertSize.mid,
status=AlertStatus.critical, status=AlertStatus.normal,
) )
@ -69,13 +75,19 @@ class AlertRenderer(Widget):
self.font_regular: rl.Font = gui_app.font(FontWeight.NORMAL) self.font_regular: rl.Font = gui_app.font(FontWeight.NORMAL)
self.font_bold: rl.Font = gui_app.font(FontWeight.BOLD) self.font_bold: rl.Font = gui_app.font(FontWeight.BOLD)
# font size is set dynamically
self._full_text1_label = Label("", font_size=0, font_weight=FontWeight.BOLD, text_alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER,
text_alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_TOP)
self._full_text2_label = Label("", font_size=ALERT_FONT_BIG, text_alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER,
text_alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_TOP)
def get_alert(self, sm: messaging.SubMaster) -> Alert | None: def get_alert(self, sm: messaging.SubMaster) -> Alert | None:
"""Generate the current alert based on selfdrive state.""" """Generate the current alert based on selfdrive state."""
ss = sm['selfdriveState'] ss = sm['selfdriveState']
# Check if selfdriveState messages have stopped arriving # Check if selfdriveState messages have stopped arriving
recv_frame = sm.recv_frame['selfdriveState']
if not sm.updated['selfdriveState']: if not sm.updated['selfdriveState']:
recv_frame = sm.recv_frame['selfdriveState']
time_since_onroad = time.monotonic() - ui_state.started_time time_since_onroad = time.monotonic() - ui_state.started_time
# 1. Never received selfdriveState since going onroad # 1. Never received selfdriveState since going onroad
@ -95,13 +107,17 @@ class AlertRenderer(Widget):
if ss.alertSize == 0: if ss.alertSize == 0:
return None return None
# Don't get old alert
if recv_frame < ui_state.started_frame:
return None
# Return current alert # Return current alert
return Alert(text1=ss.alertText1, text2=ss.alertText2, size=ss.alertSize.raw, status=ss.alertStatus.raw) return Alert(text1=ss.alertText1, text2=ss.alertText2, size=ss.alertSize.raw, status=ss.alertStatus.raw)
def _render(self, rect: rl.Rectangle) -> bool: def _render(self, rect: rl.Rectangle):
alert = self.get_alert(ui_state.sm) alert = self.get_alert(ui_state.sm)
if not alert: if not alert:
return False return
alert_rect = self._get_alert_rect(rect, alert.size) alert_rect = self._get_alert_rect(rect, alert.size)
self._draw_background(alert_rect, alert) self._draw_background(alert_rect, alert)
@ -113,21 +129,14 @@ class AlertRenderer(Widget):
alert_rect.height - 2 * ALERT_PADDING alert_rect.height - 2 * ALERT_PADDING
) )
self._draw_text(text_rect, alert) self._draw_text(text_rect, alert)
return True
def _get_alert_rect(self, rect: rl.Rectangle, size: int) -> rl.Rectangle: def _get_alert_rect(self, rect: rl.Rectangle, size: int) -> rl.Rectangle:
if size == AlertSize.full: if size == AlertSize.full:
return rect return rect
height = (ALERT_FONT_MEDIUM + 2 * ALERT_PADDING if size == AlertSize.small else h = ALERT_HEIGHTS.get(size, rect.height)
ALERT_FONT_BIG + ALERT_LINE_SPACING + ALERT_FONT_SMALL + 2 * ALERT_PADDING) return rl.Rectangle(rect.x + ALERT_MARGIN, rect.y + rect.height - h + ALERT_MARGIN,
rect.width - ALERT_MARGIN * 2, h - ALERT_MARGIN * 2)
return rl.Rectangle(
rect.x + ALERT_MARGIN,
rect.y + rect.height - ALERT_MARGIN - height,
rect.width - 2 * ALERT_MARGIN,
height
)
def _draw_background(self, rect: rl.Rectangle, alert: Alert) -> None: def _draw_background(self, rect: rl.Rectangle, alert: Alert) -> None:
color = ALERT_COLORS.get(alert.status, ALERT_COLORS[AlertStatus.normal]) color = ALERT_COLORS.get(alert.status, ALERT_COLORS[AlertStatus.normal])
@ -150,13 +159,17 @@ class AlertRenderer(Widget):
else: else:
is_long = len(alert.text1) > 15 is_long = len(alert.text1) > 15
font_size1 = 132 if is_long else 177 font_size1 = 132 if is_long else 177
align_ment = rl.GuiTextAlignment.TEXT_ALIGN_CENTER
vertical_align = rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE
text_rect = rl.Rectangle(rect.x, rect.y, rect.width, rect.height // 2)
gui_text_box(text_rect, alert.text1, font_size1, alignment=align_ment, alignment_vertical=vertical_align, font_weight=FontWeight.BOLD) top_offset = 200 if is_long or '\n' in alert.text1 else 270
text_rect.y = rect.y + rect.height // 2 title_rect = rl.Rectangle(rect.x, rect.y + top_offset, rect.width, 600)
gui_text_box(text_rect, alert.text2, ALERT_FONT_BIG, alignment=align_ment) self._full_text1_label.set_font_size(font_size1)
self._full_text1_label.set_text(alert.text1)
self._full_text1_label.render(title_rect)
bottom_offset = 361 if is_long else 420
subtitle_rect = rl.Rectangle(rect.x, rect.y + rect.height - bottom_offset, rect.width, 300)
self._full_text2_label.set_text(alert.text2)
self._full_text2_label.render(subtitle_rect)
def _draw_centered(self, text, rect, font, font_size, center_y=True, color=rl.WHITE) -> None: def _draw_centered(self, text, rect, font, font_size, center_y=True, color=rl.WHITE) -> None:
text_size = measure_text_cached(font, text, font_size) text_size = measure_text_cached(font, text, font_size)

@ -1,6 +1,7 @@
import time
import numpy as np import numpy as np
import pyray as rl import pyray as rl
from cereal import log from cereal import log, messaging
from msgq.visionipc import VisionStreamType from msgq.visionipc import VisionStreamType
from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus, UI_BORDER_SIZE from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus, UI_BORDER_SIZE
from openpilot.selfdrive.ui.onroad.alert_renderer import AlertRenderer from openpilot.selfdrive.ui.onroad.alert_renderer import AlertRenderer
@ -19,9 +20,9 @@ WIDE_CAM = VisionStreamType.VISION_STREAM_WIDE_ROAD
DEFAULT_DEVICE_CAMERA = DEVICE_CAMERAS["tici", "ar0231"] DEFAULT_DEVICE_CAMERA = DEVICE_CAMERAS["tici", "ar0231"]
BORDER_COLORS = { BORDER_COLORS = {
UIStatus.DISENGAGED: rl.Color(0x17, 0x33, 0x49, 0xC8), # Blue for disengaged state UIStatus.DISENGAGED: rl.Color(0x12, 0x28, 0x39, 0xFF), # Blue for disengaged state
UIStatus.OVERRIDE: rl.Color(0x91, 0x9B, 0x95, 0xF1), # Gray for override state UIStatus.OVERRIDE: rl.Color(0x89, 0x92, 0x8D, 0xFF), # Gray for override state
UIStatus.ENGAGED: rl.Color(0x17, 0x86, 0x44, 0xF1), # Green for engaged state UIStatus.ENGAGED: rl.Color(0x16, 0x7F, 0x40, 0xFF), # Green for engaged state
} }
WIDE_CAM_MAX_SPEED = 10.0 # m/s (22 mph) WIDE_CAM_MAX_SPEED = 10.0 # m/s (22 mph)
@ -48,8 +49,12 @@ class AugmentedRoadView(CameraView):
self.alert_renderer = AlertRenderer() self.alert_renderer = AlertRenderer()
self.driver_state_renderer = DriverStateRenderer() self.driver_state_renderer = DriverStateRenderer()
# debug
self._pm = messaging.PubMaster(['uiDebug'])
def _render(self, rect): def _render(self, rect):
# Only render when system is started to avoid invalid data access # Only render when system is started to avoid invalid data access
start_draw = time.monotonic()
if not ui_state.started: if not ui_state.started:
return return
@ -66,9 +71,6 @@ class AugmentedRoadView(CameraView):
rect.height - 2 * UI_BORDER_SIZE, rect.height - 2 * UI_BORDER_SIZE,
) )
# Draw colored border based on driving state
self._draw_border(rect)
# Enable scissor mode to clip all rendering within content rectangle boundaries # Enable scissor mode to clip all rendering within content rectangle boundaries
# This creates a rendering viewport that prevents graphics from drawing outside the border # This creates a rendering viewport that prevents graphics from drawing outside the border
rl.begin_scissor_mode( rl.begin_scissor_mode(
@ -84,8 +86,8 @@ class AugmentedRoadView(CameraView):
# Draw all UI overlays # Draw all UI overlays
self.model_renderer.render(self._content_rect) self.model_renderer.render(self._content_rect)
self._hud_renderer.render(self._content_rect) self._hud_renderer.render(self._content_rect)
if not self.alert_renderer.render(self._content_rect): self.alert_renderer.render(self._content_rect)
self.driver_state_renderer.render(self._content_rect) self.driver_state_renderer.render(self._content_rect)
# Custom UI extension point - add custom overlays here # Custom UI extension point - add custom overlays here
# Use self._content_rect for positioning within camera bounds # Use self._content_rect for positioning within camera bounds
@ -93,6 +95,14 @@ class AugmentedRoadView(CameraView):
# End clipping region # End clipping region
rl.end_scissor_mode() rl.end_scissor_mode()
# Draw colored border based on driving state
self._draw_border(rect)
# publish uiDebug
msg = messaging.new_message('uiDebug')
msg.uiDebug.drawTimeMillis = (time.monotonic() - start_draw) * 1000
self._pm.send('uiDebug', msg)
def _handle_mouse_press(self, _): def _handle_mouse_press(self, _):
if not self._hud_renderer.user_interacting() and self._click_callback is not None: if not self._hud_renderer.user_interacting() and self._click_callback is not None:
self._click_callback() self._click_callback()
@ -102,8 +112,25 @@ class AugmentedRoadView(CameraView):
pass pass
def _draw_border(self, rect: rl.Rectangle): def _draw_border(self, rect: rl.Rectangle):
rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height))
border_roundness = 0.12
border_color = BORDER_COLORS.get(ui_state.status, BORDER_COLORS[UIStatus.DISENGAGED]) border_color = BORDER_COLORS.get(ui_state.status, BORDER_COLORS[UIStatus.DISENGAGED])
rl.draw_rectangle_lines_ex(rect, UI_BORDER_SIZE, border_color) border_rect = rl.Rectangle(rect.x + UI_BORDER_SIZE, rect.y + UI_BORDER_SIZE,
rect.width - 2 * UI_BORDER_SIZE, rect.height - 2 * UI_BORDER_SIZE)
rl.draw_rectangle_rounded_lines_ex(border_rect, border_roundness, 10, UI_BORDER_SIZE, border_color)
# black bg around colored border
black_bg_thickness = UI_BORDER_SIZE
black_bg_rect = rl.Rectangle(
border_rect.x - UI_BORDER_SIZE,
border_rect.y - UI_BORDER_SIZE,
border_rect.width + 2 * UI_BORDER_SIZE,
border_rect.height + 2 * UI_BORDER_SIZE,
)
edge_offset = (black_bg_rect.height - border_rect.height) / 2 # distance between rect edges
roundness_out = (border_roundness * border_rect.height + 2 * edge_offset) / max(1.0, black_bg_rect.height)
rl.draw_rectangle_rounded_lines_ex(black_bg_rect, roundness_out, 10, black_bg_thickness, rl.BLACK)
rl.end_scissor_mode()
def _switch_stream_if_needed(self, sm): def _switch_stream_if_needed(self, sm):
if sm['selfdriveState'].experimentalMode and WIDE_CAM in self.available_streams: if sm['selfdriveState'].experimentalMode and WIDE_CAM in self.available_streams:

@ -8,6 +8,7 @@ from openpilot.system.hardware import TICI
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.egl import init_egl, create_egl_image, destroy_egl_image, bind_egl_image_to_texture, EGLImage from openpilot.system.ui.lib.egl import init_egl, create_egl_image, destroy_egl_image, bind_egl_image_to_texture, EGLImage
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.selfdrive.ui.ui_state import ui_state
CONNECTION_RETRY_INTERVAL = 0.2 # seconds between connection attempts CONNECTION_RETRY_INTERVAL = 0.2 # seconds between connection attempts
@ -67,6 +68,7 @@ else:
class CameraView(Widget): class CameraView(Widget):
def __init__(self, name: str, stream_type: VisionStreamType): def __init__(self, name: str, stream_type: VisionStreamType):
super().__init__() super().__init__()
# TODO: implement a receiver and connect thread
self._name = name self._name = name
# Primary stream # Primary stream
self.client = VisionIpcClient(name, stream_type, conflate=True) self.client = VisionIpcClient(name, stream_type, conflate=True)
@ -103,6 +105,19 @@ class CameraView(Widget):
self.egl_texture = rl.load_texture_from_image(temp_image) self.egl_texture = rl.load_texture_from_image(temp_image)
rl.unload_image(temp_image) rl.unload_image(temp_image)
ui_state.add_offroad_transition_callback(self._offroad_transition)
def _offroad_transition(self):
# Reconnect if not first time going onroad
if ui_state.is_onroad() and self.frame is not None:
# Prevent old frames from showing when going onroad. Qt has a separate thread
# which drains the VisionIpcClient SubSocket for us. Re-connecting is not enough
# and only clears internal buffers, not the message queue.
self.frame = None
if self.client:
del self.client
self.client = VisionIpcClient(self._name, self._stream_type, conflate=True)
def _set_placeholder_color(self, color: rl.Color): def _set_placeholder_color(self, color: rl.Color):
"""Set a placeholder color to be drawn when no frame is available.""" """Set a placeholder color to be drawn when no frame is available."""
self._placeholder_color = color self._placeholder_color = color

@ -3,8 +3,9 @@ import pyray as rl
from msgq.visionipc import VisionStreamType from msgq.visionipc import VisionStreamType
from openpilot.selfdrive.ui.onroad.cameraview import CameraView from openpilot.selfdrive.ui.onroad.cameraview import CameraView
from openpilot.selfdrive.ui.onroad.driver_state import DriverStateRenderer from openpilot.selfdrive.ui.onroad.driver_state import DriverStateRenderer
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state, device
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.widgets.label import gui_label from openpilot.system.ui.widgets.label import gui_label
@ -12,10 +13,17 @@ class DriverCameraDialog(CameraView):
def __init__(self): def __init__(self):
super().__init__("camerad", VisionStreamType.VISION_STREAM_DRIVER) super().__init__("camerad", VisionStreamType.VISION_STREAM_DRIVER)
self.driver_state_renderer = DriverStateRenderer() self.driver_state_renderer = DriverStateRenderer()
# TODO: this can grow unbounded, should be given some thought
device.add_interactive_timeout_callback(self.stop_dmonitoringmodeld)
ui_state.params.put_bool("IsDriverViewEnabled", True)
def stop_dmonitoringmodeld(self):
ui_state.params.put_bool("IsDriverViewEnabled", False)
gui_app.set_modal_overlay(None)
def _handle_mouse_release(self, _): def _handle_mouse_release(self, _):
super()._handle_mouse_release(_) super()._handle_mouse_release(_)
gui_app.set_modal_overlay(None) self.stop_dmonitoringmodeld()
def _render(self, rect): def _render(self, rect):
super()._render(rect) super()._render(rect)
@ -23,7 +31,7 @@ class DriverCameraDialog(CameraView):
if not self.frame: if not self.frame:
gui_label( gui_label(
rect, rect,
"camera starting", tr("camera starting"),
font_size=100, font_size=100,
font_weight=FontWeight.BOLD, font_weight=FontWeight.BOLD,
alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER,

@ -1,10 +1,13 @@
import numpy as np import numpy as np
import pyray as rl import pyray as rl
from cereal import log
from dataclasses import dataclass from dataclasses import dataclass
from openpilot.selfdrive.ui.ui_state import ui_state, UI_BORDER_SIZE from openpilot.selfdrive.ui.ui_state import ui_state, UI_BORDER_SIZE
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
AlertSize = log.SelfdriveState.AlertSize
# Default 3D coordinates for face keypoints as a NumPy array # Default 3D coordinates for face keypoints as a NumPy array
DEFAULT_FACE_KPTS_3D = np.array([ DEFAULT_FACE_KPTS_3D = np.array([
[-5.98, -51.20, 8.00], [-17.64, -49.14, 8.00], [-23.81, -46.40, 8.00], [-29.98, -40.91, 8.00], [-5.98, -51.20, 8.00], [-17.64, -49.14, 8.00], [-23.81, -46.40, 8.00], [-29.98, -40.91, 8.00],
@ -50,7 +53,6 @@ class DriverStateRenderer(Widget):
self.is_active = False self.is_active = False
self.is_rhd = False self.is_rhd = False
self.dm_fade_state = 0.0 self.dm_fade_state = 0.0
self.last_rect: rl.Rectangle = rl.Rectangle(0, 0, 0, 0)
self.driver_pose_vals = np.zeros(3, dtype=np.float32) self.driver_pose_vals = np.zeros(3, dtype=np.float32)
self.driver_pose_diff = np.zeros(3, dtype=np.float32) self.driver_pose_diff = np.zeros(3, dtype=np.float32)
self.driver_pose_sins = np.zeros(3, dtype=np.float32) self.driver_pose_sins = np.zeros(3, dtype=np.float32)
@ -75,8 +77,8 @@ class DriverStateRenderer(Widget):
self.engaged_color = rl.Color(26, 242, 66, 255) self.engaged_color = rl.Color(26, 242, 66, 255)
self.disengaged_color = rl.Color(139, 139, 139, 255) self.disengaged_color = rl.Color(139, 139, 139, 255)
self.set_visible(lambda: (ui_state.sm.recv_frame['driverStateV2'] > ui_state.started_frame and self.set_visible(lambda: (ui_state.sm["selfdriveState"].alertSize == AlertSize.none and
ui_state.sm.seen['driverMonitoringState'])) ui_state.sm.recv_frame["driverStateV2"] > ui_state.started_frame))
def _render(self, rect): def _render(self, rect):
# Set opacity based on active state # Set opacity based on active state
@ -106,11 +108,7 @@ class DriverStateRenderer(Widget):
def _update_state(self): def _update_state(self):
"""Update the driver monitoring state based on model data""" """Update the driver monitoring state based on model data"""
sm = ui_state.sm sm = ui_state.sm
if not sm.updated["driverMonitoringState"]: if not self.is_visible:
if (self._rect.x != self.last_rect.x or self._rect.y != self.last_rect.y or
self._rect.width != self.last_rect.width or self._rect.height != self.last_rect.height):
self._pre_calculate_drawing_elements()
self.last_rect = self._rect
return return
# Get monitoring state # Get monitoring state
@ -222,7 +220,7 @@ class DriverStateRenderer(Widget):
radius_y = arc_data.height / 2 radius_y = arc_data.height / 2
x_coords = center_x + np.cos(angles) * radius_x x_coords = center_x + np.cos(angles) * radius_x
y_coords = center_y + np.sin(angles) * radius_y y_coords = center_y - np.sin(angles) * radius_y
arc_lines = self.h_arc_lines if is_horizontal else self.v_arc_lines arc_lines = self.h_arc_lines if is_horizontal else self.v_arc_lines
for i, (x_coord, y_coord) in enumerate(zip(x_coords, y_coords, strict=True)): for i, (x_coord, y_coord) in enumerate(zip(x_coords, y_coords, strict=True)):

@ -66,8 +66,5 @@ class ExpButton(Widget):
if not self._params.get_bool("ExperimentalModeConfirmed"): if not self._params.get_bool("ExperimentalModeConfirmed"):
return False return False
car_params = ui_state.sm["carParams"] # Mirror exp mode toggle using persistent car params
if car_params.alphaLongitudinalAvailable: return ui_state.has_longitudinal_control
return self._params.get_bool("AlphaLongitudinalEnabled")
else:
return car_params.openpilotLongitudinalControl

@ -4,6 +4,7 @@ from openpilot.common.constants import CV
from openpilot.selfdrive.ui.onroad.exp_button import ExpButton from openpilot.selfdrive.ui.onroad.exp_button import ExpButton
from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
@ -60,7 +61,7 @@ class HudRenderer(Widget):
super().__init__() super().__init__()
"""Initialize the HUD renderer.""" """Initialize the HUD renderer."""
self.is_cruise_set: bool = False self.is_cruise_set: bool = False
self.is_cruise_available: bool = False self.is_cruise_available: bool = True
self.set_speed: float = SET_SPEED_NA self.set_speed: float = SET_SPEED_NA
self.speed: float = 0.0 self.speed: float = 0.0
self.v_ego_cluster_seen: bool = False self.v_ego_cluster_seen: bool = False
@ -130,8 +131,8 @@ class HudRenderer(Widget):
y = rect.y + 45 y = rect.y + 45
set_speed_rect = rl.Rectangle(x, y, set_speed_width, UI_CONFIG.set_speed_height) set_speed_rect = rl.Rectangle(x, y, set_speed_width, UI_CONFIG.set_speed_height)
rl.draw_rectangle_rounded(set_speed_rect, 0.2, 30, COLORS.black_translucent) rl.draw_rectangle_rounded(set_speed_rect, 0.35, 10, COLORS.black_translucent)
rl.draw_rectangle_rounded_lines_ex(set_speed_rect, 0.2, 30, 6, COLORS.border_translucent) rl.draw_rectangle_rounded_lines_ex(set_speed_rect, 0.35, 10, 6, COLORS.border_translucent)
max_color = COLORS.grey max_color = COLORS.grey
set_speed_color = COLORS.dark_grey set_speed_color = COLORS.dark_grey
@ -144,7 +145,7 @@ class HudRenderer(Widget):
elif ui_state.status == UIStatus.OVERRIDE: elif ui_state.status == UIStatus.OVERRIDE:
max_color = COLORS.override max_color = COLORS.override
max_text = "MAX" max_text = tr("MAX")
max_text_width = measure_text_cached(self._font_semi_bold, max_text, FONT_SIZES.max_speed).x max_text_width = measure_text_cached(self._font_semi_bold, max_text, FONT_SIZES.max_speed).x
rl.draw_text_ex( rl.draw_text_ex(
self._font_semi_bold, self._font_semi_bold,
@ -173,7 +174,7 @@ class HudRenderer(Widget):
speed_pos = rl.Vector2(rect.x + rect.width / 2 - speed_text_size.x / 2, 180 - speed_text_size.y / 2) speed_pos = rl.Vector2(rect.x + rect.width / 2 - speed_text_size.x / 2, 180 - speed_text_size.y / 2)
rl.draw_text_ex(self._font_bold, speed_text, speed_pos, FONT_SIZES.current_speed, 0, COLORS.white) rl.draw_text_ex(self._font_bold, speed_text, speed_pos, FONT_SIZES.current_speed, 0, COLORS.white)
unit_text = "km/h" if ui_state.is_metric else "mph" unit_text = tr("km/h") if ui_state.is_metric else tr("mph")
unit_text_size = measure_text_cached(self._font_medium, unit_text, FONT_SIZES.speed_unit) unit_text_size = measure_text_cached(self._font_medium, unit_text, FONT_SIZES.speed_unit)
unit_pos = rl.Vector2(rect.x + rect.width / 2 - unit_text_size.x / 2, 290 - unit_text_size.y / 2) unit_pos = rl.Vector2(rect.x + rect.width / 2 - unit_text_size.x / 2, 290 - unit_text_size.y / 2)
rl.draw_text_ex(self._font_medium, unit_text, unit_pos, FONT_SIZES.speed_unit, 0, COLORS.white_translucent) rl.draw_text_ex(self._font_medium, unit_text, unit_pos, FONT_SIZES.speed_unit, 0, COLORS.white_translucent)

@ -8,7 +8,7 @@ from openpilot.common.params import Params
from openpilot.selfdrive.locationd.calibrationd import HEIGHT_INIT from openpilot.selfdrive.locationd.calibrationd import HEIGHT_INIT
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.shader_polygon import draw_polygon from openpilot.system.ui.lib.shader_polygon import draw_polygon, Gradient
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
CLIP_MARGIN = 500 CLIP_MARGIN = 500
@ -66,12 +66,12 @@ class ModelRenderer(Widget):
self._transform_dirty = True self._transform_dirty = True
self._clip_region = None self._clip_region = None
self._exp_gradient = { self._exp_gradient = Gradient(
'start': (0.0, 1.0), # Bottom of path start=(0.0, 1.0), # Bottom of path
'end': (0.0, 0.0), # Top of path end=(0.0, 0.0), # Top of path
'colors': [], colors=[],
'stops': [], stops=[],
} )
# Get longitudinal control setting from car parameters # Get longitudinal control setting from car parameters
if car_params := Params().get("CarParams"): if car_params := Params().get("CarParams"):
@ -169,12 +169,12 @@ class ModelRenderer(Widget):
# Update lane lines using raw points # Update lane lines using raw points
for i, lane_line in enumerate(self._lane_lines): for i, lane_line in enumerate(self._lane_lines):
lane_line.projected_points = self._map_line_to_polygon( lane_line.projected_points = self._map_line_to_polygon(
lane_line.raw_points, 0.025 * self._lane_line_probs[i], 0.0, max_idx lane_line.raw_points, 0.025 * self._lane_line_probs[i], 0.0, max_idx, max_distance
) )
# Update road edges using raw points # Update road edges using raw points
for road_edge in self._road_edges: for road_edge in self._road_edges:
road_edge.projected_points = self._map_line_to_polygon(road_edge.raw_points, 0.025, 0.0, max_idx) road_edge.projected_points = self._map_line_to_polygon(road_edge.raw_points, 0.025, 0.0, max_idx, max_distance)
# Update path using raw points # Update path using raw points
if lead and lead.status: if lead and lead.status:
@ -183,7 +183,7 @@ class ModelRenderer(Widget):
max_idx = self._get_path_length_idx(path_x_array, max_distance) max_idx = self._get_path_length_idx(path_x_array, max_distance)
self._path.projected_points = self._map_line_to_polygon( self._path.projected_points = self._map_line_to_polygon(
self._path.raw_points, 0.9, self._path_offset_z, max_idx, allow_invert=False self._path.raw_points, 0.9, self._path_offset_z, max_idx, max_distance, allow_invert=False
) )
self._update_experimental_gradient() self._update_experimental_gradient()
@ -226,8 +226,12 @@ class ModelRenderer(Widget):
i += 1 + (1 if (i + 2) < max_len else 0) i += 1 + (1 if (i + 2) < max_len else 0)
# Store the gradient in the path object # Store the gradient in the path object
self._exp_gradient['colors'] = segment_colors self._exp_gradient = Gradient(
self._exp_gradient['stops'] = gradient_stops start=(0.0, 1.0), # Bottom of path
end=(0.0, 0.0), # Top of path
colors=segment_colors,
stops=gradient_stops,
)
def _update_lead_vehicle(self, d_rel, v_rel, point, rect): def _update_lead_vehicle(self, d_rel, v_rel, point, rect):
speed_buff, lead_buff = 10.0, 40.0 speed_buff, lead_buff = 10.0, 40.0
@ -277,12 +281,11 @@ class ModelRenderer(Widget):
return return
allow_throttle = sm['longitudinalPlan'].allowThrottle or not self._longitudinal_control allow_throttle = sm['longitudinalPlan'].allowThrottle or not self._longitudinal_control
self._blend_filter.update_dt(1 / gui_app.target_fps)
self._blend_filter.update(int(allow_throttle)) self._blend_filter.update(int(allow_throttle))
if self._experimental_mode: if self._experimental_mode:
# Draw with acceleration coloring # Draw with acceleration coloring
if len(self._exp_gradient['colors']) > 1: if len(self._exp_gradient.colors) > 1:
draw_polygon(self._rect, self._path.projected_points, gradient=self._exp_gradient) draw_polygon(self._rect, self._path.projected_points, gradient=self._exp_gradient)
else: else:
draw_polygon(self._rect, self._path.projected_points, rl.Color(255, 255, 255, 30)) draw_polygon(self._rect, self._path.projected_points, rl.Color(255, 255, 255, 30))
@ -290,12 +293,12 @@ class ModelRenderer(Widget):
# Blend throttle/no throttle colors based on transition # Blend throttle/no throttle colors based on transition
blend_factor = round(self._blend_filter.x * 100) / 100 blend_factor = round(self._blend_filter.x * 100) / 100
blended_colors = self._blend_colors(NO_THROTTLE_COLORS, THROTTLE_COLORS, blend_factor) blended_colors = self._blend_colors(NO_THROTTLE_COLORS, THROTTLE_COLORS, blend_factor)
gradient = { gradient = Gradient(
'start': (0.0, 1.0), # Bottom of path start=(0.0, 1.0), # Bottom of path
'end': (0.0, 0.0), # Top of path end=(0.0, 0.0), # Top of path
'colors': blended_colors, colors=blended_colors,
'stops': [0.0, 0.5, 1.0], stops=[0.0, 0.5, 1.0],
} )
draw_polygon(self._rect, self._path.projected_points, gradient=gradient) draw_polygon(self._rect, self._path.projected_points, gradient=gradient)
def _draw_lead_indicator(self): def _draw_lead_indicator(self):
@ -308,11 +311,11 @@ class ModelRenderer(Widget):
rl.draw_triangle_fan(lead.chevron, len(lead.chevron), rl.Color(201, 34, 49, lead.fill_alpha)) rl.draw_triangle_fan(lead.chevron, len(lead.chevron), rl.Color(201, 34, 49, lead.fill_alpha))
@staticmethod @staticmethod
def _get_path_length_idx(pos_x_array: np.ndarray, path_height: float) -> int: def _get_path_length_idx(pos_x_array: np.ndarray, path_distance: float) -> int:
"""Get the index corresponding to the given path height""" """Get the index corresponding to the given path distance"""
if len(pos_x_array) == 0: if len(pos_x_array) == 0:
return 0 return 0
indices = np.where(pos_x_array <= path_height)[0] indices = np.where(pos_x_array <= path_distance)[0]
return indices[-1] if indices.size > 0 else 0 return indices[-1] if indices.size > 0 else 0
def _map_to_screen(self, in_x, in_y, in_z): def _map_to_screen(self, in_x, in_y, in_z):
@ -331,13 +334,24 @@ class ModelRenderer(Widget):
return (x, y) return (x, y)
def _map_line_to_polygon(self, line: np.ndarray, y_off: float, z_off: float, max_idx: int, allow_invert: bool = True) -> np.ndarray: def _map_line_to_polygon(self, line: np.ndarray, y_off: float, z_off: float, max_idx: int, max_distance: float, allow_invert: bool = True) -> np.ndarray:
"""Convert 3D line to 2D polygon for rendering.""" """Convert 3D line to 2D polygon for rendering."""
if line.shape[0] == 0: if line.shape[0] == 0:
return np.empty((0, 2), dtype=np.float32) return np.empty((0, 2), dtype=np.float32)
# Slice points and filter non-negative x-coordinates # Slice points and filter non-negative x-coordinates
points = line[:max_idx + 1] points = line[:max_idx + 1]
# Interpolate around max_idx so path end is smooth (max_distance is always >= p0.x)
if 0 < max_idx < line.shape[0] - 1:
p0 = line[max_idx]
p1 = line[max_idx + 1]
x0, x1 = p0[0], p1[0]
interp_y = np.interp(max_distance, [x0, x1], [p0[1], p1[1]])
interp_z = np.interp(max_distance, [x0, x1], [p0[2], p1[2]])
interp_point = np.array([max_distance, interp_y, interp_z], dtype=points.dtype)
points = np.concatenate((points, interp_point[None, :]), axis=0)
points = points[points[:, 0] >= 0] points = points[points[:, 0] >= 0]
if points.shape[0] == 0: if points.shape[0] == 0:
return np.empty((0, 2), dtype=np.float32) return np.empty((0, 2), dtype=np.float32)

@ -4,8 +4,8 @@ set -e
UI_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"/.. UI_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"/..
TEST_TEXT="(WRAPPED_SOURCE_TEXT)" TEST_TEXT="(WRAPPED_SOURCE_TEXT)"
TEST_TS_FILE=$UI_DIR/translations/main_test_en.ts TEST_TS_FILE=$UI_DIR/translations/test_en.ts
TEST_QM_FILE=$UI_DIR/translations/main_test_en.qm TEST_QM_FILE=$UI_DIR/translations/test_en.qm
# translation strings # translation strings
UNFINISHED="<translation type=\"unfinished\"><\/translation>" UNFINISHED="<translation type=\"unfinished\"><\/translation>"

@ -7,6 +7,7 @@ import json
from openpilot.common.basedir import BASEDIR from openpilot.common.basedir import BASEDIR
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert
from openpilot.system.updated.updated import parse_release_notes
if __name__ == "__main__": if __name__ == "__main__":
params = Params() params = Params()
@ -18,9 +19,7 @@ if __name__ == "__main__":
while True: while True:
print("setting alert update") print("setting alert update")
params.put_bool("UpdateAvailable", True) params.put_bool("UpdateAvailable", True)
r = open(os.path.join(BASEDIR, "RELEASES.md")).read() params.put("UpdaterNewReleaseNotes", parse_release_notes(BASEDIR))
r = r[:r.find('\n\n')] # Slice latest release notes
params.put("UpdaterNewReleaseNotes", r + "\n")
time.sleep(t) time.sleep(t)
params.put_bool("UpdateAvailable", False) params.put_bool("UpdateAvailable", False)

@ -2,7 +2,7 @@ import time
from openpilot.selfdrive.test.helpers import with_processes from openpilot.selfdrive.test.helpers import with_processes
@with_processes(["raylib_ui"]) @with_processes(["ui"])
def test_raylib_ui(): def test_raylib_ui():
"""Test initialization of the UI widgets is successful.""" """Test initialization of the UI widgets is successful."""
time.sleep(1) time.sleep(1)

@ -10,7 +10,7 @@ int main(int argc, char **argv) {
// unit tests for Qt // unit tests for Qt
QApplication app(argc, argv); QApplication app(argc, argv);
QString language_file = "main_test_en"; QString language_file = "test_en";
// FIXME: pytest-cpp considers this print as a test case // FIXME: pytest-cpp considers this print as a test case
qDebug() << "Loading language:" << language_file; qDebug() << "Loading language:" << language_file;

@ -93,7 +93,7 @@ class TestTranslations:
def test_bad_language(self): def test_bad_language(self):
IGNORED_WORDS = {'pédale'} IGNORED_WORDS = {'pédale'}
match = re.search(r'_([a-zA-Z]{2,3})', self.file) match = re.search(r'([a-zA-Z]{2,3})', self.file)
assert match, f"{self.name} - could not parse language" assert match, f"{self.name} - could not parse language"
try: try:

@ -0,0 +1,36 @@
#!/usr/bin/env python3
"""
Simple script to print mouse coordinates on Ubuntu.
Run with: python print_mouse_coords.py
Press Ctrl+C to exit.
"""
from pynput import mouse
print("Mouse coordinate printer - Press Ctrl+C to exit")
print("Click to set the top left origin")
origin: tuple[int, int] | None = None
clicks: list[tuple[int, int]] = []
def on_click(x, y, button, pressed):
global origin, clicks
if pressed: # Only on mouse down, not up
if origin is None:
origin = (x, y)
print(f"Origin set to: {x},{y}")
else:
rel_x = x - origin[0]
rel_y = y - origin[1]
clicks.append((rel_x, rel_y))
print(f"Clicks: {clicks}")
if __name__ == "__main__":
try:
# Start mouse listener
with mouse.Listener(on_click=on_click) as listener:
listener.join()
except KeyboardInterrupt:
print("\nExiting...")

@ -9,59 +9,103 @@ from collections import namedtuple
import pyautogui import pyautogui
import pywinctl import pywinctl
from cereal import log from cereal import car, log
from cereal import messaging from cereal import messaging
from cereal.messaging import PubMaster from cereal.messaging import PubMaster
from openpilot.common.basedir import BASEDIR
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.prefix import OpenpilotPrefix
from openpilot.selfdrive.test.helpers import with_processes from openpilot.selfdrive.test.helpers import with_processes
from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert
from openpilot.system.updated.updated import parse_release_notes
AlertSize = log.SelfdriveState.AlertSize
AlertStatus = log.SelfdriveState.AlertStatus
TEST_DIR = pathlib.Path(__file__).parent TEST_DIR = pathlib.Path(__file__).parent
TEST_OUTPUT_DIR = TEST_DIR / "raylib_report" TEST_OUTPUT_DIR = TEST_DIR / "raylib_report"
SCREENSHOTS_DIR = TEST_OUTPUT_DIR / "screenshots" SCREENSHOTS_DIR = TEST_OUTPUT_DIR / "screenshots"
UI_DELAY = 0.1 UI_DELAY = 0.2
# Offroad alerts to test # Offroad alerts to test
OFFROAD_ALERTS = ['Offroad_IsTakingSnapshot'] OFFROAD_ALERTS = ['Offroad_IsTakingSnapshot']
def put_update_params(params: Params):
params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR))
params.put("UpdaterNewReleaseNotes", parse_release_notes(BASEDIR))
def setup_homescreen(click, pm: PubMaster): def setup_homescreen(click, pm: PubMaster):
pass pass
def setup_settings_device(click, pm: PubMaster): def setup_homescreen_update_available(click, pm: PubMaster):
params = Params()
params.put_bool("UpdateAvailable", True)
put_update_params(params)
setup_offroad_alert(click, pm)
def setup_settings(click, pm: PubMaster):
click(100, 100) click(100, 100)
def close_settings(click, pm: PubMaster):
click(240, 216)
def setup_settings_network(click, pm: PubMaster): def setup_settings_network(click, pm: PubMaster):
setup_settings_device(click, pm) setup_settings(click, pm)
click(278, 450) click(278, 450)
def setup_settings_network_advanced(click, pm: PubMaster):
setup_settings_network(click, pm)
click(1880, 100)
def setup_settings_toggles(click, pm: PubMaster): def setup_settings_toggles(click, pm: PubMaster):
setup_settings_device(click, pm) setup_settings(click, pm)
click(278, 600) click(278, 600)
def setup_settings_software(click, pm: PubMaster): def setup_settings_software(click, pm: PubMaster):
setup_settings_device(click, pm) put_update_params(Params())
setup_settings(click, pm)
click(278, 720) click(278, 720)
def setup_settings_software_download(click, pm: PubMaster):
params = Params()
# setup_settings_software but with "DOWNLOAD" button to test long text
params.put("UpdaterState", "idle")
params.put_bool("UpdaterFetchAvailable", True)
setup_settings_software(click, pm)
def setup_settings_software_release_notes(click, pm: PubMaster):
setup_settings_software(click, pm)
click(588, 110) # expand description for current version
def setup_settings_firehose(click, pm: PubMaster): def setup_settings_firehose(click, pm: PubMaster):
setup_settings_device(click, pm) setup_settings(click, pm)
click(278, 845) click(278, 845)
def setup_settings_developer(click, pm: PubMaster): def setup_settings_developer(click, pm: PubMaster):
setup_settings_device(click, pm) CP = car.CarParams()
CP.alphaLongitudinalAvailable = True # show alpha long control toggle
Params().put("CarParamsPersistent", CP.to_bytes())
setup_settings(click, pm)
click(278, 950) click(278, 950)
def setup_keyboard(click, pm: PubMaster): def setup_keyboard(click, pm: PubMaster):
setup_settings_developer(click, pm) setup_settings_developer(click, pm)
click(1930, 270) click(1930, 470)
def setup_pair_device(click, pm: PubMaster): def setup_pair_device(click, pm: PubMaster):
@ -69,25 +113,148 @@ def setup_pair_device(click, pm: PubMaster):
def setup_offroad_alert(click, pm: PubMaster): def setup_offroad_alert(click, pm: PubMaster):
set_offroad_alert("Offroad_TemperatureTooHigh", True, extra_text='99') put_update_params(Params())
set_offroad_alert("Offroad_TemperatureTooHigh", True, extra_text='99C')
set_offroad_alert("Offroad_ExcessiveActuation", True, extra_text='longitudinal')
for alert in OFFROAD_ALERTS: for alert in OFFROAD_ALERTS:
set_offroad_alert(alert, True) set_offroad_alert(alert, True)
setup_settings_device(click, pm) setup_settings(click, pm)
click(240, 216) close_settings(click, pm)
def setup_confirmation_dialog(click, pm: PubMaster):
setup_settings(click, pm)
click(1985, 791) # reset calibration
def setup_experimental_mode_description(click, pm: PubMaster):
setup_settings_toggles(click, pm)
click(1200, 280) # expand description for experimental mode
def setup_openpilot_long_confirmation_dialog(click, pm: PubMaster):
setup_settings_developer(click, pm)
click(2000, 960) # toggle openpilot longitudinal control
def setup_onroad(click, pm: PubMaster):
ds = messaging.new_message('deviceState')
ds.deviceState.started = True
ps = messaging.new_message('pandaStates', 1)
ps.pandaStates[0].pandaType = log.PandaState.PandaType.dos
ps.pandaStates[0].ignitionLine = True
driverState = messaging.new_message('driverStateV2')
driverState.driverStateV2.leftDriverData.faceOrientation = [0, 0, 0]
for _ in range(5):
pm.send('deviceState', ds)
pm.send('pandaStates', ps)
pm.send('driverStateV2', driverState)
ds.clear_write_flag()
ps.clear_write_flag()
driverState.clear_write_flag()
time.sleep(0.05)
def setup_onroad_sidebar(click, pm: PubMaster):
setup_onroad(click, pm)
click(100, 100) # open sidebar
def setup_onroad_small_alert(click, pm: PubMaster):
setup_onroad(click, pm)
alert = messaging.new_message('selfdriveState')
alert.selfdriveState.alertSize = AlertSize.small
alert.selfdriveState.alertText1 = "Small Alert"
alert.selfdriveState.alertText2 = "This is a small alert"
alert.selfdriveState.alertStatus = AlertStatus.normal
for _ in range(5):
pm.send('selfdriveState', alert)
alert.clear_write_flag()
time.sleep(0.05)
def setup_onroad_medium_alert(click, pm: PubMaster):
setup_onroad(click, pm)
alert = messaging.new_message('selfdriveState')
alert.selfdriveState.alertSize = AlertSize.mid
alert.selfdriveState.alertText1 = "Medium Alert"
alert.selfdriveState.alertText2 = "This is a medium alert"
alert.selfdriveState.alertStatus = AlertStatus.userPrompt
for _ in range(5):
pm.send('selfdriveState', alert)
alert.clear_write_flag()
time.sleep(0.05)
def setup_onroad_full_alert(click, pm: PubMaster):
setup_onroad(click, pm)
alert = messaging.new_message('selfdriveState')
alert.selfdriveState.alertSize = AlertSize.full
alert.selfdriveState.alertText1 = "DISENGAGE IMMEDIATELY"
alert.selfdriveState.alertText2 = "Driver Distracted"
alert.selfdriveState.alertStatus = AlertStatus.critical
for _ in range(5):
pm.send('selfdriveState', alert)
alert.clear_write_flag()
time.sleep(0.05)
def setup_onroad_full_alert_multiline(click, pm: PubMaster):
setup_onroad(click, pm)
alert = messaging.new_message('selfdriveState')
alert.selfdriveState.alertSize = AlertSize.full
alert.selfdriveState.alertText1 = "Reverse\nGear"
alert.selfdriveState.alertStatus = AlertStatus.normal
for _ in range(5):
pm.send('selfdriveState', alert)
alert.clear_write_flag()
time.sleep(0.05)
def setup_onroad_full_alert_long_text(click, pm: PubMaster):
setup_onroad(click, pm)
alert = messaging.new_message('selfdriveState')
alert.selfdriveState.alertSize = AlertSize.full
alert.selfdriveState.alertText1 = "TAKE CONTROL IMMEDIATELY"
alert.selfdriveState.alertText2 = "Calibration Invalid: Remount Device & Recalibrate"
alert.selfdriveState.alertStatus = AlertStatus.userPrompt
for _ in range(5):
pm.send('selfdriveState', alert)
alert.clear_write_flag()
time.sleep(0.05)
CASES = { CASES = {
"homescreen": setup_homescreen, "homescreen": setup_homescreen,
"settings_device": setup_settings_device, "homescreen_paired": setup_homescreen,
"homescreen_prime": setup_homescreen,
"homescreen_update_available": setup_homescreen_update_available,
"settings_device": setup_settings,
"settings_network": setup_settings_network, "settings_network": setup_settings_network,
"settings_network_advanced": setup_settings_network_advanced,
"settings_toggles": setup_settings_toggles, "settings_toggles": setup_settings_toggles,
"settings_software": setup_settings_software, "settings_software": setup_settings_software,
"settings_software_download": setup_settings_software_download,
"settings_software_release_notes": setup_settings_software_release_notes,
"settings_firehose": setup_settings_firehose, "settings_firehose": setup_settings_firehose,
"settings_developer": setup_settings_developer, "settings_developer": setup_settings_developer,
"keyboard": setup_keyboard, "keyboard": setup_keyboard,
"pair_device": setup_pair_device, "pair_device": setup_pair_device,
"offroad_alert": setup_offroad_alert, "offroad_alert": setup_offroad_alert,
"confirmation_dialog": setup_confirmation_dialog,
"experimental_mode_description": setup_experimental_mode_description,
"openpilot_long_confirmation_dialog": setup_openpilot_long_confirmation_dialog,
"onroad": setup_onroad,
"onroad_sidebar": setup_onroad_sidebar,
"onroad_small_alert": setup_onroad_small_alert,
"onroad_medium_alert": setup_onroad_medium_alert,
"onroad_full_alert": setup_onroad_full_alert,
"onroad_full_alert_multiline": setup_onroad_full_alert_multiline,
"onroad_full_alert_long_text": setup_onroad_full_alert_long_text,
} }
@ -98,7 +265,7 @@ class TestUI:
def setup(self): def setup(self):
# Seed minimal offroad state # Seed minimal offroad state
self.pm = PubMaster(["deviceState"]) self.pm = PubMaster(["deviceState", "pandaStates", "driverStateV2", "selfdriveState"])
ds = messaging.new_message('deviceState') ds = messaging.new_message('deviceState')
ds.deviceState.networkType = log.DeviceState.NetworkType.wifi ds.deviceState.networkType = log.DeviceState.NetworkType.wifi
for _ in range(5): for _ in range(5):
@ -122,9 +289,10 @@ class TestUI:
time.sleep(0.01) time.sleep(0.01)
pyautogui.mouseUp(self.ui.left + x, self.ui.top + y, *args, **kwargs) pyautogui.mouseUp(self.ui.left + x, self.ui.top + y, *args, **kwargs)
@with_processes(["raylib_ui"]) @with_processes(["ui"])
def test_ui(self, name, setup_case): def test_ui(self, name, setup_case):
self.setup() self.setup()
time.sleep(UI_DELAY) # wait for UI to start
setup_case(self.click, self.pm) setup_case(self.click, self.pm)
self.screenshot(name) self.screenshot(name)
@ -135,10 +303,21 @@ def create_screenshots():
SCREENSHOTS_DIR.mkdir(parents=True) SCREENSHOTS_DIR.mkdir(parents=True)
t = TestUI() t = TestUI()
with OpenpilotPrefix(): for name, setup in CASES.items():
params = Params() with OpenpilotPrefix():
params.put("DongleId", "123456789012345") params = Params()
for name, setup in CASES.items(): params.put("DongleId", "123456789012345")
# Set branch name
description = "0.10.1 / this-is-a-really-super-mega-long-branch-name / 7864838 / Oct 03"
params.put("UpdaterCurrentDescription", description)
params.put("UpdaterNewDescription", description)
if name == "homescreen_paired":
params.put("PrimeType", 0) # NONE
elif name == "homescreen_prime":
params.put("PrimeType", 2) # LITE
t.test_ui(name, setup) t.test_ui(name, setup)

@ -26,7 +26,7 @@ def get_language_files(languages: list[str] = None) -> dict[str, pathlib.Path]:
for filename in language_dict.values(): for filename in language_dict.values():
path = TRANSLATIONS_DIR / f"{filename}.ts" path = TRANSLATIONS_DIR / f"{filename}.ts"
language = path.stem.split("main_")[1] language = path.stem
if languages is None or language in languages: if languages is None or language in languages:
files[language] = path files[language] = path

@ -1,14 +1,14 @@
{ {
"English": "main_en", "English": "en",
"Deutsch": "main_de", "Deutsch": "de",
"Français": "main_fr", "Français": "fr",
"Português": "main_pt-BR", "Português": "pt-BR",
"Español": "main_es", "Español": "es",
"Türkçe": "main_tr", "Türkçe": "tr",
"العربية": "main_ar", "العربية": "ar",
"ไทย": "main_th", "ไทย": "th",
"中文(繁體)": "main_zh-CHT", "中文(繁體)": "zh-CHT",
"中文(简体)": "main_zh-CHS", "中文(简体)": "zh-CHS",
"한국어": "main_ko", "한국어": "ko",
"日本語": "main_ja" "日本語": "ja"
} }

@ -1,20 +1,20 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import pyray as rl import pyray as rl
from openpilot.common.watchdog import kick_watchdog
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.selfdrive.ui.layouts.main import MainLayout from openpilot.selfdrive.ui.layouts.main import MainLayout
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
def main(): def main():
# TODO: https://github.com/commaai/agnos-builder/pull/490
# os.nice(-20)
gui_app.init_window("UI") gui_app.init_window("UI")
main_layout = MainLayout() main_layout = MainLayout()
main_layout.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) main_layout.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height))
for showing_dialog in gui_app.render(): for showing_dialog in gui_app.render():
ui_state.update() ui_state.update()
kick_watchdog()
if not showing_dialog: if not showing_dialog:
main_layout.render() main_layout.render()

@ -4,13 +4,13 @@ import time
import threading import threading
from collections.abc import Callable from collections.abc import Callable
from enum import Enum from enum import Enum
from cereal import messaging, log from cereal import messaging, car, log
from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.filter_simple import FirstOrderFilter
from openpilot.common.params import Params, UnknownKeyName from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.selfdrive.ui.lib.prime_state import PrimeState from openpilot.selfdrive.ui.lib.prime_state import PrimeState
from openpilot.system.hardware import HARDWARE
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.hardware import HARDWARE
UI_BORDER_SIZE = 30 UI_BORDER_SIZE = 30
BACKLIGHT_OFFROAD = 50 BACKLIGHT_OFFROAD = 50
@ -50,6 +50,7 @@ class UIState:
"managerState", "managerState",
"selfdriveState", "selfdriveState",
"longitudinalPlan", "longitudinalPlan",
"rawAudioData",
] ]
) )
@ -66,11 +67,25 @@ class UIState:
self.is_metric: bool = self.params.get_bool("IsMetric") self.is_metric: bool = self.params.get_bool("IsMetric")
self.started: bool = False self.started: bool = False
self.ignition: bool = False self.ignition: bool = False
self.recording_audio: bool = False
self.panda_type: log.PandaState.PandaType = log.PandaState.PandaType.unknown self.panda_type: log.PandaState.PandaType = log.PandaState.PandaType.unknown
self.personality: log.LongitudinalPersonality = log.LongitudinalPersonality.standard self.personality: log.LongitudinalPersonality = log.LongitudinalPersonality.standard
self.has_longitudinal_control: bool = False
self.CP: car.CarParams | None = None
self.light_sensor: float = -1.0 self.light_sensor: float = -1.0
self._param_update_time: float = 0.0
# Callbacks
self._offroad_transition_callbacks: list[Callable[[], None]] = []
self._engaged_transition_callbacks: list[Callable[[], None]] = []
self._update_params() self.update_params()
def add_offroad_transition_callback(self, callback: Callable[[], None]):
self._offroad_transition_callbacks.append(callback)
def add_engaged_transition_callback(self, callback: Callable[[], None]):
self._engaged_transition_callbacks.append(callback)
@property @property
def engaged(self) -> bool: def engaged(self) -> bool:
@ -86,6 +101,8 @@ class UIState:
self.sm.update(0) self.sm.update(0)
self._update_state() self._update_state()
self._update_status() self._update_status()
if time.monotonic() - self._param_update_time > 5.0:
self.update_params()
device.update() device.update()
def _update_state(self) -> None: def _update_state(self) -> None:
@ -112,6 +129,11 @@ class UIState:
# Update started state # Update started state
self.started = self.sm["deviceState"].started and self.ignition self.started = self.sm["deviceState"].started and self.ignition
# Update recording audio state
self.recording_audio = self.params.get_bool("RecordAudio") and self.started
self.is_metric = self.params.get_bool("IsMetric")
def _update_status(self) -> None: def _update_status(self) -> None:
if self.started and self.sm.updated["selfdriveState"]: if self.started and self.sm.updated["selfdriveState"]:
ss = self.sm["selfdriveState"] ss = self.sm["selfdriveState"]
@ -124,6 +146,8 @@ class UIState:
# Check for engagement state changes # Check for engagement state changes
if self.engaged != self._engaged_prev: if self.engaged != self._engaged_prev:
for callback in self._engaged_transition_callbacks:
callback()
self._engaged_prev = self.engaged self._engaged_prev = self.engaged
# Handle onroad/offroad transition # Handle onroad/offroad transition
@ -133,13 +157,22 @@ class UIState:
self.started_frame = self.sm.frame self.started_frame = self.sm.frame
self.started_time = time.monotonic() self.started_time = time.monotonic()
for callback in self._offroad_transition_callbacks:
callback()
self._started_prev = self.started self._started_prev = self.started
def _update_params(self) -> None: def update_params(self) -> None:
try: # For slower operations
self.is_metric = self.params.get_bool("IsMetric") # Update longitudinal control state
except UnknownKeyName: CP_bytes = self.params.get("CarParamsPersistent")
self.is_metric = False if CP_bytes is not None:
self.CP = messaging.log_from_bytes(CP_bytes, car.CarParams)
if self.CP.alphaLongitudinalAvailable:
self.has_longitudinal_control = self.params.get_bool("AlphaLongitudinalEnabled")
else:
self.has_longitudinal_control = self.CP.openpilotLongitudinalControl
self._param_update_time = time.monotonic()
class Device: class Device:
@ -189,14 +222,12 @@ class Device:
clipped_brightness = float(np.clip(100 * clipped_brightness, 10, 100)) clipped_brightness = float(np.clip(100 * clipped_brightness, 10, 100))
self._brightness_filter.update_dt(1 / gui_app.target_fps)
brightness = round(self._brightness_filter.update(clipped_brightness)) brightness = round(self._brightness_filter.update(clipped_brightness))
if not self._awake: if not self._awake:
brightness = 0 brightness = 0
if brightness != self._last_brightness: if brightness != self._last_brightness:
if self._brightness_thread is None or not self._brightness_thread.is_alive(): if self._brightness_thread is None or not self._brightness_thread.is_alive():
cloudlog.debug(f"setting display brightness {brightness}")
self._brightness_thread = threading.Thread(target=HARDWARE.set_screen_brightness, args=(brightness,)) self._brightness_thread = threading.Thread(target=HARDWARE.set_screen_brightness, args=(brightness,))
self._brightness_thread.start() self._brightness_thread.start()
self._last_brightness = brightness self._last_brightness = brightness

@ -4,12 +4,10 @@ import json
import os import os
from openpilot.common.basedir import BASEDIR from openpilot.common.basedir import BASEDIR
from openpilot.system.ui.lib.multilang import UI_DIR, TRANSLATIONS_DIR, LANGUAGES_FILE
UI_DIR = os.path.join(BASEDIR, "selfdrive", "ui")
TRANSLATIONS_DIR = os.path.join(UI_DIR, "translations")
LANGUAGES_FILE = os.path.join(TRANSLATIONS_DIR, "languages.json")
TRANSLATIONS_INCLUDE_FILE = os.path.join(TRANSLATIONS_DIR, "alerts_generated.h") TRANSLATIONS_INCLUDE_FILE = os.path.join(TRANSLATIONS_DIR, "alerts_generated.h")
PLURAL_ONLY = ["main_en"] # base language, only create entries for strings with plural forms PLURAL_ONLY = ["en"] # base language, only create entries for strings with plural forms
def generate_translations_include(): def generate_translations_include():

@ -1,6 +1,7 @@
import pyray as rl import pyray as rl
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
@ -9,7 +10,7 @@ class ExperimentalModeButton(Widget):
super().__init__() super().__init__()
self.img_width = 80 self.img_width = 80
self.horizontal_padding = 50 self.horizontal_padding = 25
self.button_height = 125 self.button_height = 125
self.params = Params() self.params = Params()
@ -18,6 +19,9 @@ class ExperimentalModeButton(Widget):
self.chill_pixmap = gui_app.texture("icons/couch.png", self.img_width, self.img_width) self.chill_pixmap = gui_app.texture("icons/couch.png", self.img_width, self.img_width)
self.experimental_pixmap = gui_app.texture("icons/experimental_grey.png", self.img_width, self.img_width) self.experimental_pixmap = gui_app.texture("icons/experimental_grey.png", self.img_width, self.img_width)
def show_event(self):
self.experimental_mode = self.params.get_bool("ExperimentalMode")
def _get_gradient_colors(self): def _get_gradient_colors(self):
alpha = 0xCC if self.is_pressed else 0xFF alpha = 0xCC if self.is_pressed else 0xFF
@ -31,16 +35,10 @@ class ExperimentalModeButton(Widget):
rl.draw_rectangle_gradient_h(int(rect.x), int(rect.y), int(rect.width), int(rect.height), rl.draw_rectangle_gradient_h(int(rect.x), int(rect.y), int(rect.width), int(rect.height),
start_color, end_color) start_color, end_color)
def _handle_mouse_release(self, mouse_pos):
self.experimental_mode = not self.experimental_mode
# TODO: Opening settings for ExperimentalMode
self.params.put_bool("ExperimentalMode", self.experimental_mode)
def _render(self, rect): def _render(self, rect):
rl.draw_rectangle_rounded(rect, 0.08, 20, rl.WHITE)
rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height)) rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height))
self._draw_gradient_background(rect) self._draw_gradient_background(rect)
rl.draw_rectangle_rounded_lines_ex(self._rect, 0.19, 10, 5, rl.BLACK)
rl.end_scissor_mode() rl.end_scissor_mode()
# Draw vertical separator line # Draw vertical separator line
@ -49,9 +47,9 @@ class ExperimentalModeButton(Widget):
rl.draw_line_ex(rl.Vector2(line_x, rect.y), rl.Vector2(line_x, rect.y + rect.height), 3, separator_color) rl.draw_line_ex(rl.Vector2(line_x, rect.y), rl.Vector2(line_x, rect.y + rect.height), 3, separator_color)
# Draw text label (left aligned) # Draw text label (left aligned)
text = "EXPERIMENTAL MODE ON" if self.experimental_mode else "CHILL MODE ON" text = tr("EXPERIMENTAL MODE ON") if self.experimental_mode else tr("CHILL MODE ON")
text_x = rect.x + self.horizontal_padding text_x = rect.x + self.horizontal_padding
text_y = rect.y + rect.height / 2 - 45 // 2 # Center vertically text_y = rect.y + rect.height / 2 - 45 * FONT_SCALE // 2 # Center vertically
rl.draw_text_ex(gui_app.font(FontWeight.NORMAL), text, rl.Vector2(int(text_x), int(text_y)), 45, 0, rl.BLACK) rl.draw_text_ex(gui_app.font(FontWeight.NORMAL), text, rl.Vector2(int(text_x), int(text_y)), 45, 0, rl.BLACK)

@ -1,37 +1,45 @@
import pyray as rl import pyray as rl
from enum import IntEnum
from abc import ABC, abstractmethod from abc import ABC, abstractmethod
from collections.abc import Callable from collections.abc import Callable
from dataclasses import dataclass from dataclasses import dataclass
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.system.hardware import HARDWARE from openpilot.system.hardware import HARDWARE
from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.wrap_text import wrap_text
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.html_render import HtmlRenderer
from openpilot.selfdrive.selfdrived.alertmanager import OFFROAD_ALERTS from openpilot.selfdrive.selfdrived.alertmanager import OFFROAD_ALERTS
NO_RELEASE_NOTES = tr("<h2>No release notes available.</h2>")
class AlertColors: class AlertColors:
HIGH_SEVERITY = rl.Color(226, 44, 44, 255) HIGH_SEVERITY = rl.Color(226, 44, 44, 255)
LOW_SEVERITY = rl.Color(41, 41, 41, 255) LOW_SEVERITY = rl.Color(41, 41, 41, 255)
BACKGROUND = rl.Color(57, 57, 57, 255) BACKGROUND = rl.Color(57, 57, 57, 255)
BUTTON = rl.WHITE BUTTON = rl.WHITE
BUTTON_PRESSED = rl.Color(200, 200, 200, 255)
BUTTON_TEXT = rl.BLACK BUTTON_TEXT = rl.BLACK
SNOOZE_BG = rl.Color(79, 79, 79, 255) SNOOZE_BG = rl.Color(79, 79, 79, 255)
SNOOZE_BG_PRESSED = rl.Color(100, 100, 100, 255)
TEXT = rl.WHITE TEXT = rl.WHITE
class AlertConstants: class AlertConstants:
BUTTON_SIZE = (400, 125) MIN_BUTTON_WIDTH = 400
SNOOZE_BUTTON_SIZE = (550, 125) BUTTON_HEIGHT = 125
REBOOT_BUTTON_SIZE = (600, 125)
MARGIN = 50 MARGIN = 50
SPACING = 30 SPACING = 30
FONT_SIZE = 48 FONT_SIZE = 48
BORDER_RADIUS = 30 BORDER_RADIUS = 30 * 2 # matches Qt's 30px
ALERT_HEIGHT = 120 ALERT_HEIGHT = 120
ALERT_SPACING = 20 ALERT_SPACING = 10
ALERT_INSET = 60
@dataclass @dataclass
@ -42,6 +50,41 @@ class AlertData:
visible: bool = False visible: bool = False
class ButtonStyle(IntEnum):
LIGHT = 0
DARK = 1
class ActionButton(Widget):
def __init__(self, text: str, style: ButtonStyle = ButtonStyle.LIGHT,
min_width: int = AlertConstants.MIN_BUTTON_WIDTH):
super().__init__()
self._style = style
self._min_width = min_width
self._font = gui_app.font(FontWeight.MEDIUM)
self.set_text(text)
def set_text(self, text: str):
self._text = text
self._text_size = measure_text_cached(gui_app.font(FontWeight.MEDIUM), self._text, AlertConstants.FONT_SIZE)
self._rect.width = max(self._text_size.x + 60 * 2, self._min_width)
self._rect.height = AlertConstants.BUTTON_HEIGHT
def _render(self, _):
roundness = AlertConstants.BORDER_RADIUS / self._rect.height
bg_color = AlertColors.BUTTON if self._style == ButtonStyle.LIGHT else AlertColors.SNOOZE_BG
if self.is_pressed:
bg_color = AlertColors.BUTTON_PRESSED if self._style == ButtonStyle.LIGHT else AlertColors.SNOOZE_BG_PRESSED
rl.draw_rectangle_rounded(self._rect, roundness, 10, bg_color)
# center text
color = rl.WHITE if self._style == ButtonStyle.DARK else rl.BLACK
text_x = int(self._rect.x + (self._rect.width - self._text_size.x) // 2)
text_y = int(self._rect.y + (self._rect.height - self._text_size.y) // 2)
rl.draw_text_ex(self._font, self._text, rl.Vector2(text_x, text_y), AlertConstants.FONT_SIZE, 0, color)
class AbstractAlert(Widget, ABC): class AbstractAlert(Widget, ABC):
def __init__(self, has_reboot_btn: bool = False): def __init__(self, has_reboot_btn: bool = False):
super().__init__() super().__init__()
@ -49,17 +92,38 @@ class AbstractAlert(Widget, ABC):
self.has_reboot_btn = has_reboot_btn self.has_reboot_btn = has_reboot_btn
self.dismiss_callback: Callable | None = None self.dismiss_callback: Callable | None = None
self.dismiss_btn_rect = rl.Rectangle(0, 0, *AlertConstants.BUTTON_SIZE) def snooze_callback():
self.snooze_btn_rect = rl.Rectangle(0, 0, *AlertConstants.SNOOZE_BUTTON_SIZE) self.params.put_bool("SnoozeUpdate", True)
self.reboot_btn_rect = rl.Rectangle(0, 0, *AlertConstants.REBOOT_BUTTON_SIZE) if self.dismiss_callback:
self.dismiss_callback()
def excessive_actuation_callback():
self.params.remove("Offroad_ExcessiveActuation")
if self.dismiss_callback:
self.dismiss_callback()
self.dismiss_btn = ActionButton(tr("Close"))
self.snooze_btn = ActionButton(tr("Snooze Update"), style=ButtonStyle.DARK)
self.snooze_btn.set_click_callback(snooze_callback)
self.excessive_actuation_btn = ActionButton(tr("Acknowledge Excessive Actuation"), style=ButtonStyle.DARK, min_width=800)
self.excessive_actuation_btn.set_click_callback(excessive_actuation_callback)
self.reboot_btn = ActionButton(tr("Reboot and Update"), min_width=600)
self.reboot_btn.set_click_callback(lambda: HARDWARE.reboot())
self.snooze_visible = False # TODO: just use a Scroller?
self.content_rect = rl.Rectangle(0, 0, 0, 0) self.content_rect = rl.Rectangle(0, 0, 0, 0)
self.scroll_panel_rect = rl.Rectangle(0, 0, 0, 0) self.scroll_panel_rect = rl.Rectangle(0, 0, 0, 0)
self.scroll_panel = GuiScrollPanel() self.scroll_panel = GuiScrollPanel()
def show_event(self):
self.scroll_panel.set_offset(0)
def set_dismiss_callback(self, callback: Callable): def set_dismiss_callback(self, callback: Callable):
self.dismiss_callback = callback self.dismiss_callback = callback
self.dismiss_btn.set_click_callback(self.dismiss_callback)
@abstractmethod @abstractmethod
def refresh(self) -> bool: def refresh(self) -> bool:
@ -69,28 +133,10 @@ class AbstractAlert(Widget, ABC):
def get_content_height(self) -> float: def get_content_height(self) -> float:
pass pass
def _handle_mouse_release(self, mouse_pos: MousePos):
super()._handle_mouse_release(mouse_pos)
if not self.scroll_panel.is_touch_valid():
return
if rl.check_collision_point_rec(mouse_pos, self.dismiss_btn_rect):
if self.dismiss_callback:
self.dismiss_callback()
elif self.snooze_visible and rl.check_collision_point_rec(mouse_pos, self.snooze_btn_rect):
self.params.put_bool("SnoozeUpdate", True)
if self.dismiss_callback:
self.dismiss_callback()
elif self.has_reboot_btn and rl.check_collision_point_rec(mouse_pos, self.reboot_btn_rect):
HARDWARE.reboot()
def _render(self, rect: rl.Rectangle): def _render(self, rect: rl.Rectangle):
rl.draw_rectangle_rounded(rect, AlertConstants.BORDER_RADIUS / rect.width, 10, AlertColors.BACKGROUND) rl.draw_rectangle_rounded(rect, AlertConstants.BORDER_RADIUS / rect.height, 10, AlertColors.BACKGROUND)
footer_height = AlertConstants.BUTTON_SIZE[1] + AlertConstants.SPACING footer_height = AlertConstants.BUTTON_HEIGHT + AlertConstants.SPACING
content_height = rect.height - 2 * AlertConstants.MARGIN - footer_height content_height = rect.height - 2 * AlertConstants.MARGIN - footer_height
self.content_rect = rl.Rectangle( self.content_rect = rl.Rectangle(
@ -109,7 +155,7 @@ class AbstractAlert(Widget, ABC):
def _render_scrollable_content(self): def _render_scrollable_content(self):
content_total_height = self.get_content_height() content_total_height = self.get_content_height()
content_bounds = rl.Rectangle(0, 0, self.scroll_panel_rect.width, content_total_height) content_bounds = rl.Rectangle(0, 0, self.scroll_panel_rect.width, content_total_height)
scroll_offset = self.scroll_panel.handle_scroll(self.scroll_panel_rect, content_bounds) scroll_offset = self.scroll_panel.update(self.scroll_panel_rect, content_bounds)
rl.begin_scissor_mode( rl.begin_scissor_mode(
int(self.scroll_panel_rect.x), int(self.scroll_panel_rect.x),
@ -120,7 +166,7 @@ class AbstractAlert(Widget, ABC):
content_rect_with_scroll = rl.Rectangle( content_rect_with_scroll = rl.Rectangle(
self.scroll_panel_rect.x, self.scroll_panel_rect.x,
self.scroll_panel_rect.y + scroll_offset.y, self.scroll_panel_rect.y + scroll_offset,
self.scroll_panel_rect.width, self.scroll_panel_rect.width,
content_total_height, content_total_height,
) )
@ -133,44 +179,26 @@ class AbstractAlert(Widget, ABC):
pass pass
def _render_footer(self, rect: rl.Rectangle): def _render_footer(self, rect: rl.Rectangle):
footer_y = rect.y + rect.height - AlertConstants.MARGIN - AlertConstants.BUTTON_SIZE[1] footer_y = rect.y + rect.height - AlertConstants.MARGIN - AlertConstants.BUTTON_HEIGHT
font = gui_app.font(FontWeight.MEDIUM)
self.dismiss_btn_rect.x = rect.x + AlertConstants.MARGIN
self.dismiss_btn_rect.y = footer_y
rl.draw_rectangle_rounded(self.dismiss_btn_rect, 0.3, 10, AlertColors.BUTTON)
text = "Close"
text_width = measure_text_cached(font, text, AlertConstants.FONT_SIZE).x
text_x = self.dismiss_btn_rect.x + (AlertConstants.BUTTON_SIZE[0] - text_width) // 2
text_y = self.dismiss_btn_rect.y + (AlertConstants.BUTTON_SIZE[1] - AlertConstants.FONT_SIZE) // 2
rl.draw_text_ex(
font, text, rl.Vector2(int(text_x), int(text_y)), AlertConstants.FONT_SIZE, 0, AlertColors.BUTTON_TEXT
)
if self.snooze_visible: dismiss_x = rect.x + AlertConstants.MARGIN
self.snooze_btn_rect.x = rect.x + rect.width - AlertConstants.MARGIN - AlertConstants.SNOOZE_BUTTON_SIZE[0] self.dismiss_btn.set_position(dismiss_x, footer_y)
self.snooze_btn_rect.y = footer_y self.dismiss_btn.render()
rl.draw_rectangle_rounded(self.snooze_btn_rect, 0.3, 10, AlertColors.SNOOZE_BG)
if self.has_reboot_btn:
text = "Snooze Update" reboot_x = rect.x + rect.width - AlertConstants.MARGIN - self.reboot_btn.rect.width
text_width = measure_text_cached(font, text, AlertConstants.FONT_SIZE).x self.reboot_btn.set_position(reboot_x, footer_y)
text_x = self.snooze_btn_rect.x + (AlertConstants.SNOOZE_BUTTON_SIZE[0] - text_width) // 2 self.reboot_btn.render()
text_y = self.snooze_btn_rect.y + (AlertConstants.SNOOZE_BUTTON_SIZE[1] - AlertConstants.FONT_SIZE) // 2
rl.draw_text_ex(font, text, rl.Vector2(int(text_x), int(text_y)), AlertConstants.FONT_SIZE, 0, AlertColors.TEXT) elif self.excessive_actuation_btn.is_visible:
actuation_x = rect.x + rect.width - AlertConstants.MARGIN - self.excessive_actuation_btn.rect.width
elif self.has_reboot_btn: self.excessive_actuation_btn.set_position(actuation_x, footer_y)
self.reboot_btn_rect.x = rect.x + rect.width - AlertConstants.MARGIN - AlertConstants.REBOOT_BUTTON_SIZE[0] self.excessive_actuation_btn.render()
self.reboot_btn_rect.y = footer_y
rl.draw_rectangle_rounded(self.reboot_btn_rect, 0.3, 10, AlertColors.BUTTON) elif self.snooze_btn.is_visible:
snooze_x = rect.x + rect.width - AlertConstants.MARGIN - self.snooze_btn.rect.width
text = "Reboot and Update" self.snooze_btn.set_position(snooze_x, footer_y)
text_width = measure_text_cached(font, text, AlertConstants.FONT_SIZE).x self.snooze_btn.render()
text_x = self.reboot_btn_rect.x + (AlertConstants.REBOOT_BUTTON_SIZE[0] - text_width) // 2
text_y = self.reboot_btn_rect.y + (AlertConstants.REBOOT_BUTTON_SIZE[1] - AlertConstants.FONT_SIZE) // 2
rl.draw_text_ex(
font, text, rl.Vector2(int(text_x), int(text_y)), AlertConstants.FONT_SIZE, 0, AlertColors.BUTTON_TEXT
)
class OffroadAlert(AbstractAlert): class OffroadAlert(AbstractAlert):
@ -184,13 +212,14 @@ class OffroadAlert(AbstractAlert):
active_count = 0 active_count = 0
connectivity_needed = False connectivity_needed = False
excessive_actuation = False
for alert_data in self.sorted_alerts: for alert_data in self.sorted_alerts:
text = "" text = ""
alert_json = self.params.get(alert_data.key) alert_json = self.params.get(alert_data.key)
if alert_json: if alert_json:
text = alert_json.get("text", "").replace("{}", alert_json.get("extra", "")) text = alert_json.get("text", "").replace("%1", alert_json.get("extra", ""))
alert_data.text = text alert_data.text = text
alert_data.visible = bool(text) alert_data.visible = bool(text)
@ -201,7 +230,11 @@ class OffroadAlert(AbstractAlert):
if alert_data.key == "Offroad_ConnectivityNeeded" and alert_data.visible: if alert_data.key == "Offroad_ConnectivityNeeded" and alert_data.visible:
connectivity_needed = True connectivity_needed = True
self.snooze_visible = connectivity_needed if alert_data.key == "Offroad_ExcessiveActuation" and alert_data.visible:
excessive_actuation = True
self.excessive_actuation_btn.set_visible(excessive_actuation)
self.snooze_btn.set_visible(connectivity_needed and not excessive_actuation)
return active_count return active_count
def get_content_height(self) -> float: def get_content_height(self) -> float:
@ -215,12 +248,12 @@ class OffroadAlert(AbstractAlert):
if not alert_data.visible: if not alert_data.visible:
continue continue
text_width = int(self.content_rect.width - 90) text_width = int(self.content_rect.width - (AlertConstants.ALERT_INSET * 2))
wrapped_lines = wrap_text(font, alert_data.text, AlertConstants.FONT_SIZE, text_width) wrapped_lines = wrap_text(font, alert_data.text, AlertConstants.FONT_SIZE, text_width)
line_count = len(wrapped_lines) line_count = len(wrapped_lines)
text_height = line_count * (AlertConstants.FONT_SIZE + 5) text_height = line_count * (AlertConstants.FONT_SIZE * FONT_SCALE)
alert_item_height = max(text_height + 40, AlertConstants.ALERT_HEIGHT) alert_item_height = max(text_height + (AlertConstants.ALERT_INSET * 2), AlertConstants.ALERT_HEIGHT)
total_height += alert_item_height + AlertConstants.ALERT_SPACING total_height += round(alert_item_height + AlertConstants.ALERT_SPACING)
if total_height > 20: if total_height > 20:
total_height = total_height - AlertConstants.ALERT_SPACING + 20 total_height = total_height - AlertConstants.ALERT_SPACING + 20
@ -235,7 +268,7 @@ class OffroadAlert(AbstractAlert):
self.sorted_alerts.append(alert_data) self.sorted_alerts.append(alert_data)
def _render_content(self, content_rect: rl.Rectangle): def _render_content(self, content_rect: rl.Rectangle):
y_offset = 20 y_offset = AlertConstants.ALERT_SPACING
font = gui_app.font(FontWeight.NORMAL) font = gui_app.font(FontWeight.NORMAL)
for alert_data in self.sorted_alerts: for alert_data in self.sorted_alerts:
@ -243,11 +276,11 @@ class OffroadAlert(AbstractAlert):
continue continue
bg_color = AlertColors.HIGH_SEVERITY if alert_data.severity > 0 else AlertColors.LOW_SEVERITY bg_color = AlertColors.HIGH_SEVERITY if alert_data.severity > 0 else AlertColors.LOW_SEVERITY
text_width = int(content_rect.width - 90) text_width = int(content_rect.width - (AlertConstants.ALERT_INSET * 2))
wrapped_lines = wrap_text(font, alert_data.text, AlertConstants.FONT_SIZE, text_width) wrapped_lines = wrap_text(font, alert_data.text, AlertConstants.FONT_SIZE, text_width)
line_count = len(wrapped_lines) line_count = len(wrapped_lines)
text_height = line_count * (AlertConstants.FONT_SIZE + 5) text_height = line_count * (AlertConstants.FONT_SIZE * FONT_SCALE)
alert_item_height = max(text_height + 40, AlertConstants.ALERT_HEIGHT) alert_item_height = max(text_height + (AlertConstants.ALERT_INSET * 2), AlertConstants.ALERT_HEIGHT)
alert_rect = rl.Rectangle( alert_rect = rl.Rectangle(
content_rect.x + 10, content_rect.x + 10,
@ -256,22 +289,23 @@ class OffroadAlert(AbstractAlert):
alert_item_height, alert_item_height,
) )
rl.draw_rectangle_rounded(alert_rect, 0.2, 10, bg_color) roundness = AlertConstants.BORDER_RADIUS / min(alert_rect.height, alert_rect.width)
rl.draw_rectangle_rounded(alert_rect, roundness, 10, bg_color)
text_x = alert_rect.x + 30 text_x = alert_rect.x + AlertConstants.ALERT_INSET
text_y = alert_rect.y + 20 text_y = alert_rect.y + AlertConstants.ALERT_INSET
for i, line in enumerate(wrapped_lines): for i, line in enumerate(wrapped_lines):
rl.draw_text_ex( rl.draw_text_ex(
font, font,
line, line,
rl.Vector2(text_x, text_y + i * (AlertConstants.FONT_SIZE + 5)), rl.Vector2(text_x, text_y + i * AlertConstants.FONT_SIZE * FONT_SCALE),
AlertConstants.FONT_SIZE, AlertConstants.FONT_SIZE,
0, 0,
AlertColors.TEXT, AlertColors.TEXT,
) )
y_offset += alert_item_height + AlertConstants.ALERT_SPACING y_offset += round(alert_item_height + AlertConstants.ALERT_SPACING)
class UpdateAlert(AbstractAlert): class UpdateAlert(AbstractAlert):
@ -280,12 +314,16 @@ class UpdateAlert(AbstractAlert):
self.release_notes = "" self.release_notes = ""
self._wrapped_release_notes = "" self._wrapped_release_notes = ""
self._cached_content_height: float = 0.0 self._cached_content_height: float = 0.0
self._html_renderer = HtmlRenderer(text="")
def refresh(self) -> bool: def refresh(self) -> bool:
update_available: bool = self.params.get_bool("UpdateAvailable") update_available: bool = self.params.get_bool("UpdateAvailable")
if update_available: if update_available:
self.release_notes = self.params.get("UpdaterNewReleaseNotes") self.release_notes = (self.params.get("UpdaterNewReleaseNotes") or b"").decode("utf8").strip()
self._html_renderer.parse_html_content(self.release_notes or NO_RELEASE_NOTES)
self._cached_content_height = 0 self._cached_content_height = 0
else:
self._html_renderer.parse_html_content(NO_RELEASE_NOTES)
return update_available return update_available
@ -301,18 +339,5 @@ class UpdateAlert(AbstractAlert):
return self._cached_content_height return self._cached_content_height
def _render_content(self, content_rect: rl.Rectangle): def _render_content(self, content_rect: rl.Rectangle):
if self.release_notes: notes_rect = rl.Rectangle(content_rect.x + 30, content_rect.y + 30, content_rect.width - 60, content_rect.height - 60)
rl.draw_text_ex( self._html_renderer.render(notes_rect)
gui_app.font(FontWeight.NORMAL),
self._wrapped_release_notes,
rl.Vector2(content_rect.x + 30, content_rect.y + 30),
AlertConstants.FONT_SIZE,
0.0,
AlertColors.TEXT,
)
else:
no_notes_text = "No release notes available."
text_width = rl.measure_text(no_notes_text, AlertConstants.FONT_SIZE)
text_x = content_rect.x + (content_rect.width - text_width) // 2
text_y = content_rect.y + 50
rl.draw_text(no_notes_text, int(text_x), int(text_y), AlertConstants.FONT_SIZE, AlertColors.TEXT)

@ -8,11 +8,24 @@ from openpilot.common.swaglog import cloudlog
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.lib.application import FontWeight, gui_app from openpilot.system.ui.lib.application import FontWeight, gui_app
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.wrap_text import wrap_text
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
class IconButton(Widget):
def __init__(self, texture: rl.Texture):
super().__init__()
self._texture = texture
def _render(self, rect: rl.Rectangle):
color = rl.Color(180, 180, 180, 150) if self.is_pressed else rl.WHITE
draw_x = rect.x + (rect.width - self._texture.width) / 2
draw_y = rect.y + (rect.height - self._texture.height) / 2
rl.draw_texture(self._texture, int(draw_x), int(draw_y), color)
class PairingDialog(Widget): class PairingDialog(Widget):
"""Dialog for device pairing with QR code.""" """Dialog for device pairing with QR code."""
@ -22,14 +35,16 @@ class PairingDialog(Widget):
super().__init__() super().__init__()
self.params = Params() self.params = Params()
self.qr_texture: rl.Texture | None = None self.qr_texture: rl.Texture | None = None
self.last_qr_generation = 0 self.last_qr_generation = float('-inf')
self._close_btn = IconButton(gui_app.texture("icons/close.png", 80, 80))
self._close_btn.set_click_callback(lambda: gui_app.set_modal_overlay(None))
def _get_pairing_url(self) -> str: def _get_pairing_url(self) -> str:
try: try:
dongle_id = self.params.get("DongleId") or "" dongle_id = self.params.get("DongleId") or ""
token = Api(dongle_id).get_token({'pair': True}) token = Api(dongle_id).get_token({'pair': True})
except Exception as e: except Exception:
cloudlog.warning(f"Failed to get pairing token: {e}") cloudlog.exception("Failed to get pairing token")
token = "" token = ""
return f"https://connect.comma.ai/?pair={token}" return f"https://connect.comma.ai/?pair={token}"
@ -53,8 +68,8 @@ class PairingDialog(Widget):
rl_image.format = rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_R8G8B8A8 rl_image.format = rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_R8G8B8A8
self.qr_texture = rl.load_texture_from_image(rl_image) self.qr_texture = rl.load_texture_from_image(rl_image)
except Exception as e: except Exception:
cloudlog.warning(f"QR code generation failed: {e}") cloudlog.exception("QR code generation failed")
self.qr_texture = None self.qr_texture = None
def _check_qr_refresh(self) -> None: def _check_qr_refresh(self) -> None:
@ -78,24 +93,14 @@ class PairingDialog(Widget):
# Close button # Close button
close_size = 80 close_size = 80
close_icon = gui_app.texture("icons/close.png", close_size, close_size) pad = 20
close_rect = rl.Rectangle(content_rect.x, y, close_size, close_size) close_rect = rl.Rectangle(content_rect.x - pad, y - pad, close_size + pad * 2, close_size + pad * 2)
self._close_btn.render(close_rect)
mouse_pos = rl.get_mouse_position()
is_hover = rl.check_collision_point_rec(mouse_pos, close_rect)
is_pressed = rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT)
is_released = rl.is_mouse_button_released(rl.MouseButton.MOUSE_BUTTON_LEFT)
color = rl.Color(180, 180, 180, 150) if (is_hover and is_pressed) else rl.WHITE
rl.draw_texture(close_icon, int(content_rect.x), int(y), color)
if (is_hover and is_released) or rl.is_key_pressed(rl.KeyboardKey.KEY_ESCAPE):
return 1
y += close_size + 40 y += close_size + 40
# Title # Title
title = "Pair your device to your comma account" title = tr("Pair your device to your comma account")
title_font = gui_app.font(FontWeight.NORMAL) title_font = gui_app.font(FontWeight.NORMAL)
left_width = int(content_rect.width * 0.5 - 15) left_width = int(content_rect.width * 0.5 - 15)
@ -120,9 +125,9 @@ class PairingDialog(Widget):
def _render_instructions(self, rect: rl.Rectangle) -> None: def _render_instructions(self, rect: rl.Rectangle) -> None:
instructions = [ instructions = [
"Go to https://connect.comma.ai on your phone", tr("Go to https://connect.comma.ai on your phone"),
"Click \"add new device\" and scan the QR code on the right", tr("Click \"add new device\" and scan the QR code on the right"),
"Bookmark connect.comma.ai to your home screen to use it like an app", tr("Bookmark connect.comma.ai to your home screen to use it like an app"),
] ]
font = gui_app.font(FontWeight.BOLD) font = gui_app.font(FontWeight.BOLD)
@ -141,8 +146,8 @@ class PairingDialog(Widget):
# Circle and number # Circle and number
rl.draw_circle(int(circle_x), int(circle_y), circle_radius, rl.Color(70, 70, 70, 255)) rl.draw_circle(int(circle_x), int(circle_y), circle_radius, rl.Color(70, 70, 70, 255))
number = str(i + 1) number = str(i + 1)
number_width = measure_text_cached(font, number, 30).x number_size = measure_text_cached(font, number, 30)
rl.draw_text(number, int(circle_x - number_width // 2), int(circle_y - 15), 30, rl.WHITE) rl.draw_text_ex(font, number, (int(circle_x - number_size.x // 2), int(circle_y - number_size.y // 2)), 30, 0, rl.WHITE)
# Text # Text
rl.draw_text_ex(font, "\n".join(wrapped), rl.Vector2(text_x, y), 47, 0.0, rl.BLACK) rl.draw_text_ex(font, "\n".join(wrapped), rl.Vector2(text_x, y), 47, 0.0, rl.BLACK)
@ -153,7 +158,7 @@ class PairingDialog(Widget):
rl.draw_rectangle_rounded(rect, 0.1, 20, rl.Color(240, 240, 240, 255)) rl.draw_rectangle_rounded(rect, 0.1, 20, rl.Color(240, 240, 240, 255))
error_font = gui_app.font(FontWeight.BOLD) error_font = gui_app.font(FontWeight.BOLD)
rl.draw_text_ex( rl.draw_text_ex(
error_font, "QR Code Error", rl.Vector2(rect.x + 20, rect.y + rect.height // 2 - 15), 30, 0.0, rl.RED error_font, tr("QR Code Error"), rl.Vector2(rect.x + 20, rect.y + rect.height // 2 - 15), 30, 0.0, rl.RED
) )
return return

@ -2,6 +2,7 @@ import pyray as rl
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.wrap_text import wrap_text
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
@ -22,41 +23,41 @@ class PrimeWidget(Widget):
def _render_for_non_prime_users(self, rect: rl.Rectangle): def _render_for_non_prime_users(self, rect: rl.Rectangle):
"""Renders the advertisement for non-Prime users.""" """Renders the advertisement for non-Prime users."""
rl.draw_rectangle_rounded(rect, 0.02, 10, self.PRIME_BG_COLOR) rl.draw_rectangle_rounded(rect, 0.025, 10, self.PRIME_BG_COLOR)
# Layout # Layout
x, y = rect.x + 80, rect.y + 90 x, y = rect.x + 80, rect.y + 90
w = rect.width - 160 w = rect.width - 160
# Title # Title
gui_label(rl.Rectangle(x, y, w, 90), "Upgrade Now", 75, font_weight=FontWeight.BOLD) gui_label(rl.Rectangle(x, y, w, 90), tr("Upgrade Now"), 75, font_weight=FontWeight.BOLD)
# Description with wrapping # Description with wrapping
desc_y = y + 140 desc_y = y + 140
font = gui_app.font(FontWeight.LIGHT) font = gui_app.font(FontWeight.LIGHT)
wrapped_text = "\n".join(wrap_text(font, "Become a comma prime member at connect.comma.ai", 56, int(w))) wrapped_text = "\n".join(wrap_text(font, tr("Become a comma prime member at connect.comma.ai"), 56, int(w)))
text_size = measure_text_cached(font, wrapped_text, 56) text_size = measure_text_cached(font, wrapped_text, 56)
rl.draw_text_ex(font, wrapped_text, rl.Vector2(x, desc_y), 56, 0, rl.WHITE) rl.draw_text_ex(font, wrapped_text, rl.Vector2(x, desc_y), 56, 0, rl.WHITE)
# Features section # Features section
features_y = desc_y + text_size.y + 50 features_y = desc_y + text_size.y + 50
gui_label(rl.Rectangle(x, features_y, w, 50), "PRIME FEATURES:", 41, font_weight=FontWeight.BOLD) gui_label(rl.Rectangle(x, features_y, w, 50), tr("PRIME FEATURES:"), 41, font_weight=FontWeight.BOLD)
# Feature list # Feature list
features = ["Remote access", "24/7 LTE connectivity", "1 year of drive storage", "Remote snapshots"] features = [tr("Remote access"), tr("24/7 LTE connectivity"), tr("1 year of drive storage"), tr("Remote snapshots")]
for i, feature in enumerate(features): for i, feature in enumerate(features):
item_y = features_y + 80 + i * 65 item_y = features_y + 80 + i * 65
gui_label(rl.Rectangle(x, item_y, 50, 60), "", 50, color=rl.Color(70, 91, 234, 255)) gui_label(rl.Rectangle(x, item_y, 100, 60), "", 50, color=rl.Color(70, 91, 234, 255))
gui_label(rl.Rectangle(x + 60, item_y, w - 60, 60), feature, 50) gui_label(rl.Rectangle(x + 60, item_y, w - 60, 60), feature, 50)
def _render_for_prime_user(self, rect: rl.Rectangle): def _render_for_prime_user(self, rect: rl.Rectangle):
"""Renders the prime user widget with subscription status.""" """Renders the prime user widget with subscription status."""
rl.draw_rectangle_rounded(rl.Rectangle(rect.x, rect.y, rect.width, 230), 0.02, 10, self.PRIME_BG_COLOR) rl.draw_rectangle_rounded(rl.Rectangle(rect.x, rect.y, rect.width, 230), 0.1, 10, self.PRIME_BG_COLOR)
x = rect.x + 56 x = rect.x + 56
y = rect.y + 40 y = rect.y + 40
font = gui_app.font(FontWeight.BOLD) font = gui_app.font(FontWeight.BOLD)
rl.draw_text_ex(font, "✓ SUBSCRIBED", rl.Vector2(x, y), 41, 0, rl.Color(134, 255, 78, 255)) rl.draw_text_ex(font, tr("✓ SUBSCRIBED"), rl.Vector2(x, y), 41, 0, rl.Color(134, 255, 78, 255))
rl.draw_text_ex(font, "comma prime", rl.Vector2(x, y + 61), 75, 0, rl.WHITE) rl.draw_text_ex(font, tr("comma prime"), rl.Vector2(x, y + 61), 75, 0, rl.WHITE)

@ -1,10 +1,14 @@
import pyray as rl import pyray as rl
from openpilot.common.time_helpers import system_time_valid
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
from openpilot.selfdrive.ui.widgets.pairing_dialog import PairingDialog from openpilot.selfdrive.ui.widgets.pairing_dialog import PairingDialog
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.wrap_text import wrap_text
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.confirm_dialog import alert_dialog
from openpilot.system.ui.widgets.button import Button, ButtonStyle from openpilot.system.ui.widgets.button import Button, ButtonStyle
from openpilot.system.ui.widgets.label import Label
class SetupWidget(Widget): class SetupWidget(Widget):
@ -12,9 +16,10 @@ class SetupWidget(Widget):
super().__init__() super().__init__()
self._open_settings_callback = None self._open_settings_callback = None
self._pairing_dialog: PairingDialog | None = None self._pairing_dialog: PairingDialog | None = None
self._pair_device_btn = Button("Pair device", self._show_pairing, button_style=ButtonStyle.PRIMARY) self._pair_device_btn = Button(tr("Pair device"), self._show_pairing, button_style=ButtonStyle.PRIMARY)
self._open_settings_btn = Button("Open", lambda: self._open_settings_callback() if self._open_settings_callback else None, self._open_settings_btn = Button(tr("Open"), lambda: self._open_settings_callback() if self._open_settings_callback else None,
button_style=ButtonStyle.PRIMARY) button_style=ButtonStyle.PRIMARY)
self._firehose_label = Label(tr("🔥 Firehose Mode 🔥"), font_weight=FontWeight.MEDIUM, font_size=64)
def set_open_settings_callback(self, callback): def set_open_settings_callback(self, callback):
self._open_settings_callback = callback self._open_settings_callback = callback
@ -28,7 +33,7 @@ class SetupWidget(Widget):
def _render_registration(self, rect: rl.Rectangle): def _render_registration(self, rect: rl.Rectangle):
"""Render registration prompt.""" """Render registration prompt."""
rl.draw_rectangle_rounded(rl.Rectangle(rect.x, rect.y, rect.width, 590), 0.02, 20, rl.Color(51, 51, 51, 255)) rl.draw_rectangle_rounded(rl.Rectangle(rect.x, rect.y, rect.width, rect.height), 0.03, 20, rl.Color(51, 51, 51, 255))
x = rect.x + 64 x = rect.x + 64
y = rect.y + 48 y = rect.y + 48
@ -36,24 +41,24 @@ class SetupWidget(Widget):
# Title # Title
font = gui_app.font(FontWeight.BOLD) font = gui_app.font(FontWeight.BOLD)
rl.draw_text_ex(font, "Finish Setup", rl.Vector2(x, y), 75, 0, rl.WHITE) rl.draw_text_ex(font, tr("Finish Setup"), rl.Vector2(x, y), 75, 0, rl.WHITE)
y += 113 # 75 + 38 spacing y += 113 # 75 + 38 spacing
# Description # Description
desc = "Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer." desc = tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.")
light_font = gui_app.font(FontWeight.LIGHT) light_font = gui_app.font(FontWeight.LIGHT)
wrapped = wrap_text(light_font, desc, 50, int(w)) wrapped = wrap_text(light_font, desc, 50, int(w))
for line in wrapped: for line in wrapped:
rl.draw_text_ex(light_font, line, rl.Vector2(x, y), 50, 0, rl.WHITE) rl.draw_text_ex(light_font, line, rl.Vector2(x, y), 50, 0, rl.WHITE)
y += 50 y += 50 * FONT_SCALE
button_rect = rl.Rectangle(x, y + 50, w, 128) button_rect = rl.Rectangle(x, y + 30, w, 200)
self._pair_device_btn.render(button_rect) self._pair_device_btn.render(button_rect)
def _render_firehose_prompt(self, rect: rl.Rectangle): def _render_firehose_prompt(self, rect: rl.Rectangle):
"""Render firehose prompt widget.""" """Render firehose prompt widget."""
rl.draw_rectangle_rounded(rl.Rectangle(rect.x, rect.y, rect.width, 450), 0.02, 20, rl.Color(51, 51, 51, 255)) rl.draw_rectangle_rounded(rl.Rectangle(rect.x, rect.y, rect.width, 500), 0.04, 20, rl.Color(51, 51, 51, 255))
# Content margins (56, 40, 56, 40) # Content margins (56, 40, 56, 40)
x = rect.x + 56 x = rect.x + 56
@ -62,19 +67,17 @@ class SetupWidget(Widget):
spacing = 42 spacing = 42
# Title with fire emojis # Title with fire emojis
title_font = gui_app.font(FontWeight.MEDIUM) self._firehose_label.render(rl.Rectangle(rect.x, y, rect.width, 64))
title_text = "Firehose Mode"
rl.draw_text_ex(title_font, title_text, rl.Vector2(x, y), 64, 0, rl.WHITE)
y += 64 + spacing y += 64 + spacing
# Description # Description
desc_font = gui_app.font(FontWeight.NORMAL) desc_font = gui_app.font(FontWeight.NORMAL)
desc_text = "Maximize your training data uploads to improve openpilot's driving models." desc_text = tr("Maximize your training data uploads to improve openpilot's driving models.")
wrapped_desc = wrap_text(desc_font, desc_text, 40, int(w)) wrapped_desc = wrap_text(desc_font, desc_text, 40, int(w))
for line in wrapped_desc: for line in wrapped_desc:
rl.draw_text_ex(desc_font, line, rl.Vector2(x, y), 40, 0, rl.WHITE) rl.draw_text_ex(desc_font, line, rl.Vector2(x, y), 40, 0, rl.WHITE)
y += 40 y += 40 * FONT_SCALE
y += spacing y += spacing
@ -84,6 +87,11 @@ class SetupWidget(Widget):
self._open_settings_btn.render(button_rect) self._open_settings_btn.render(button_rect)
def _show_pairing(self): def _show_pairing(self):
if not system_time_valid():
dlg = alert_dialog(tr("Please connect to Wi-Fi to complete initial pairing"))
gui_app.set_modal_overlay(dlg)
return
if not self._pairing_dialog: if not self._pairing_dialog:
self._pairing_dialog = PairingDialog() self._pairing_dialog = PairingDialog()
gui_app.set_modal_overlay(self._pairing_dialog, lambda result: setattr(self, '_pairing_dialog', None)) gui_app.set_modal_overlay(self._pairing_dialog, lambda result: setattr(self, '_pairing_dialog', None))

@ -2,13 +2,15 @@ import pyray as rl
import requests import requests
import threading import threading
import copy import copy
from collections.abc import Callable
from enum import Enum from enum import Enum
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.multilang import tr
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.widgets import DialogResult from openpilot.system.ui.widgets import DialogResult
from openpilot.system.ui.widgets.button import gui_button, ButtonStyle from openpilot.system.ui.widgets.button import Button, ButtonStyle
from openpilot.system.ui.widgets.confirm_dialog import alert_dialog from openpilot.system.ui.widgets.confirm_dialog import alert_dialog
from openpilot.system.ui.widgets.keyboard import Keyboard from openpilot.system.ui.widgets.keyboard import Keyboard
from openpilot.system.ui.widgets.list_view import ( from openpilot.system.ui.widgets.list_view import (
@ -20,11 +22,13 @@ from openpilot.system.ui.widgets.list_view import (
BUTTON_WIDTH, BUTTON_WIDTH,
) )
VALUE_FONT_SIZE = 48
class SshKeyActionState(Enum): class SshKeyActionState(Enum):
LOADING = "LOADING" LOADING = tr("LOADING")
ADD = "ADD" ADD = tr("ADD")
REMOVE = "REMOVE" REMOVE = tr("REMOVE")
class SshKeyAction(ItemAction): class SshKeyAction(ItemAction):
@ -34,13 +38,19 @@ class SshKeyAction(ItemAction):
def __init__(self): def __init__(self):
super().__init__(self.MAX_WIDTH, True) super().__init__(self.MAX_WIDTH, True)
self._keyboard = Keyboard() self._keyboard = Keyboard(min_text_size=1)
self._params = Params() self._params = Params()
self._error_message: str = "" self._error_message: str = ""
self._text_font = gui_app.font(FontWeight.MEDIUM) self._text_font = gui_app.font(FontWeight.NORMAL)
self._button = Button("", click_callback=self._handle_button_click, button_style=ButtonStyle.LIST_ACTION,
border_radius=BUTTON_BORDER_RADIUS, font_size=BUTTON_FONT_SIZE)
self._refresh_state() self._refresh_state()
def set_touch_valid_callback(self, touch_callback: Callable[[], bool]) -> None:
super().set_touch_valid_callback(touch_callback)
self._button.set_touch_valid_callback(touch_callback)
def _refresh_state(self): def _refresh_state(self):
self._username = self._params.get("GithubUsername") self._username = self._params.get("GithubUsername")
self._state = SshKeyActionState.REMOVE if self._params.get("GithubSshKeys") else SshKeyActionState.ADD self._state = SshKeyActionState.REMOVE if self._params.get("GithubSshKeys") else SshKeyActionState.ADD
@ -49,41 +59,34 @@ class SshKeyAction(ItemAction):
# Show error dialog if there's an error # Show error dialog if there's an error
if self._error_message: if self._error_message:
message = copy.copy(self._error_message) message = copy.copy(self._error_message)
gui_app.set_modal_overlay(lambda: alert_dialog(message)) gui_app.set_modal_overlay(alert_dialog(message))
self._username = "" self._username = ""
self._error_message = "" self._error_message = ""
# Draw username if exists # Draw username if exists
if self._username: if self._username:
text_size = measure_text_cached(self._text_font, self._username, BUTTON_FONT_SIZE) text_size = measure_text_cached(self._text_font, self._username, VALUE_FONT_SIZE)
rl.draw_text_ex( rl.draw_text_ex(
self._text_font, self._text_font,
self._username, self._username,
(rect.x + rect.width - BUTTON_WIDTH - text_size.x - 30, rect.y + (rect.height - text_size.y) / 2), (rect.x + rect.width - BUTTON_WIDTH - text_size.x - 30, rect.y + (rect.height - text_size.y) / 2),
BUTTON_FONT_SIZE, VALUE_FONT_SIZE,
1.0, 1.0,
rl.WHITE, rl.Color(170, 170, 170, 255),
) )
# Draw button # Draw button
if gui_button( button_rect = rl.Rectangle(rect.x + rect.width - BUTTON_WIDTH, rect.y + (rect.height - BUTTON_HEIGHT) / 2, BUTTON_WIDTH, BUTTON_HEIGHT)
rl.Rectangle( self._button.set_rect(button_rect)
rect.x + rect.width - BUTTON_WIDTH, rect.y + (rect.height - BUTTON_HEIGHT) / 2, BUTTON_WIDTH, BUTTON_HEIGHT self._button.set_text(self._state.value)
), self._button.set_enabled(self._state != SshKeyActionState.LOADING)
self._state.value, self._button.render(button_rect)
is_enabled=self._state != SshKeyActionState.LOADING,
border_radius=BUTTON_BORDER_RADIUS,
font_size=BUTTON_FONT_SIZE,
button_style=ButtonStyle.LIST_ACTION,
):
self._handle_button_click()
return True
return False return False
def _handle_button_click(self): def _handle_button_click(self):
if self._state == SshKeyActionState.ADD: if self._state == SshKeyActionState.ADD:
self._keyboard.clear() self._keyboard.reset()
self._keyboard.set_title("Enter your GitHub username") self._keyboard.set_title(tr("Enter your GitHub username"))
gui_app.set_modal_overlay(self._keyboard, callback=self._on_username_submit) gui_app.set_modal_overlay(self._keyboard, callback=self._on_username_submit)
elif self._state == SshKeyActionState.REMOVE: elif self._state == SshKeyActionState.REMOVE:
self._params.remove("GithubUsername") self._params.remove("GithubUsername")
@ -108,7 +111,7 @@ class SshKeyAction(ItemAction):
response.raise_for_status() response.raise_for_status()
keys = response.text.strip() keys = response.text.strip()
if not keys: if not keys:
raise requests.exceptions.HTTPError("No SSH keys found") raise requests.exceptions.HTTPError(tr("No SSH keys found"))
# Success - save keys # Success - save keys
self._params.put("GithubUsername", username) self._params.put("GithubUsername", username)
@ -117,10 +120,10 @@ class SshKeyAction(ItemAction):
self._username = username self._username = username
except requests.exceptions.Timeout: except requests.exceptions.Timeout:
self._error_message = "Request timed out" self._error_message = tr("Request timed out")
self._state = SshKeyActionState.ADD self._state = SshKeyActionState.ADD
except Exception: except Exception:
self._error_message = f"No SSH keys found for user '{username}'" self._error_message = tr("No SSH keys found for user '{}'").format(username)
self._state = SshKeyActionState.ADD self._state = SshKeyActionState.ADD

@ -89,7 +89,7 @@ void CameraState::set_exposure_rect() {
// set areas for each camera, shouldn't be changed // set areas for each camera, shouldn't be changed
std::vector<std::pair<Rect, float>> ae_targets = { std::vector<std::pair<Rect, float>> ae_targets = {
// (Rect, F) // (Rect, F)
std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide std::make_pair((Rect){96, 400, 1734, 524}, 567.0), // wide
std::make_pair((Rect){96, 160, 1734, 986}, 2648.0), // road std::make_pair((Rect){96, 160, 1734, 986}, 2648.0), // road
std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver
}; };

@ -18,7 +18,7 @@ class TiciFanController(BaseFanController):
cloudlog.info("Setting up TICI fan handler") cloudlog.info("Setting up TICI fan handler")
self.last_ignition = False self.last_ignition = False
self.controller = PIDController(k_p=0, k_i=4e-3, k_f=1, rate=(1 / DT_HW)) self.controller = PIDController(k_p=0, k_i=4e-3, rate=(1 / DT_HW))
def update(self, cur_temp: float, ignition: bool) -> int: def update(self, cur_temp: float, ignition: bool) -> int:
self.controller.pos_limit = 100 if ignition else 30 self.controller.pos_limit = 100 if ignition else 30

@ -1,25 +1,25 @@
[ [
{ {
"name": "xbl", "name": "xbl",
"url": "https://commadist.azureedge.net/agnosupdate/xbl-effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/xbl-98e0642e2af77596e64d107b2c525a36e54d41d879268fd2fcab9255a2b29723.img.xz",
"hash": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", "hash": "98e0642e2af77596e64d107b2c525a36e54d41d879268fd2fcab9255a2b29723",
"hash_raw": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", "hash_raw": "98e0642e2af77596e64d107b2c525a36e54d41d879268fd2fcab9255a2b29723",
"size": 3282256, "size": 3282256,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "ed61a650bea0c56652dd0fc68465d8fc722a4e6489dc8f257630c42c6adcdc89" "ondevice_hash": "907c705f72ebcbd3030e03da9ef4c65a3d599e056a79aa9e7c369fdff8e54dc4"
}, },
{ {
"name": "xbl_config", "name": "xbl_config",
"url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-4d8add65e80b3e5ca49a64fac76025ee3a57a1523abd9caa407aa8c5fb721b0f.img.xz",
"hash": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", "hash": "4d8add65e80b3e5ca49a64fac76025ee3a57a1523abd9caa407aa8c5fb721b0f",
"hash_raw": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", "hash_raw": "4d8add65e80b3e5ca49a64fac76025ee3a57a1523abd9caa407aa8c5fb721b0f",
"size": 98124, "size": 98124,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "b12801ffaa81e58e3cef914488d3b447e35483ba549b28c6cd9deb4814c3265f" "ondevice_hash": "46c472f52fb97a4836d08d0e790f5c8512651f520ce004bc3bbc6a143fc7a3c2"
}, },
{ {
"name": "abl", "name": "abl",
@ -34,51 +34,51 @@
}, },
{ {
"name": "aop", "name": "aop",
"url": "https://commadist.azureedge.net/agnosupdate/aop-21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/aop-d8add1d4c1b6b443debf7bb80040e88a12140d248a328650d65ceaa0df04c1b7.img.xz",
"hash": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", "hash": "d8add1d4c1b6b443debf7bb80040e88a12140d248a328650d65ceaa0df04c1b7",
"hash_raw": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", "hash_raw": "d8add1d4c1b6b443debf7bb80040e88a12140d248a328650d65ceaa0df04c1b7",
"size": 184364, "size": 184364,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "c1be2f4aac5b3af49b904b027faec418d05efd7bd5144eb4fdfcba602bcf2180" "ondevice_hash": "e320da0d3f73aa09277a8be740c59f9cc605d2098b46a842c93ea2ac0ac97cb0"
}, },
{ {
"name": "devcfg", "name": "devcfg",
"url": "https://commadist.azureedge.net/agnosupdate/devcfg-d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/devcfg-7e8a836cf75a9097b1c78960d36f883699fcc3858d8a1d28338f889f6af25cc8.img.xz",
"hash": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", "hash": "7e8a836cf75a9097b1c78960d36f883699fcc3858d8a1d28338f889f6af25cc8",
"hash_raw": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", "hash_raw": "7e8a836cf75a9097b1c78960d36f883699fcc3858d8a1d28338f889f6af25cc8",
"size": 40336, "size": 40336,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "17b229668b20305ff8fa3cd5f94716a3aaa1e5bf9d1c24117eff7f2f81ae719f" "ondevice_hash": "7e9412d154036216e56c2346d24455dd45f56d6de4c9e8837597f22d59c83d93"
}, },
{ {
"name": "boot", "name": "boot",
"url": "https://commadist.azureedge.net/agnosupdate/boot-b96882012ab6cddda04f440009c798a6cff65977f984b12072e89afa592d86cb.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/boot-08291eb52a9d54b77e191ea1a78addf24aae28e15306ac3118d03ac9be29fbe9.img.xz",
"hash": "b96882012ab6cddda04f440009c798a6cff65977f984b12072e89afa592d86cb", "hash": "08291eb52a9d54b77e191ea1a78addf24aae28e15306ac3118d03ac9be29fbe9",
"hash_raw": "b96882012ab6cddda04f440009c798a6cff65977f984b12072e89afa592d86cb", "hash_raw": "08291eb52a9d54b77e191ea1a78addf24aae28e15306ac3118d03ac9be29fbe9",
"size": 17442816, "size": 17868800,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "8ed6c2796be5c5b29d64e6413b8e878d5bd1a3981d15216d2b5e84140cc4ea2a" "ondevice_hash": "18fab2e1eb2e43e5c39e20ee20e0d391586de528df6dbfdab6dabcdab835ee3e"
}, },
{ {
"name": "system", "name": "system",
"url": "https://commadist.azureedge.net/agnosupdate/system-2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/system-1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b.img.xz",
"hash": "325414e5c9f7516b2bf0fedb6abe6682f717897a6d84ab70d5afe91a59f244e9", "hash": "8d4b4dd80a8a537adf82faa07928066bec4568eae73bdcf4a5f0da94fb77b485",
"hash_raw": "2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc", "hash_raw": "1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b",
"size": 4718592000, "size": 5368709120,
"sparse": true, "sparse": true,
"full_check": false, "full_check": false,
"has_ab": true, "has_ab": true,
"ondevice_hash": "79f4f6d0b5b4a416f0f31261b430943a78e37c26d0e226e0ef412fe0eae3c727", "ondevice_hash": "a9569b9286fba882be003f9710383ae6de229a72db936e80be08dbd2c23f320e",
"alt": { "alt": {
"hash": "2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc", "hash": "1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b",
"url": "https://commadist.azureedge.net/agnosupdate/system-2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc.img", "url": "https://commadist.azureedge.net/agnosupdate/system-1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b.img",
"size": 4718592000 "size": 5368709120
} }
} }
] ]

@ -130,25 +130,25 @@
}, },
{ {
"name": "xbl", "name": "xbl",
"url": "https://commadist.azureedge.net/agnosupdate/xbl-effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/xbl-98e0642e2af77596e64d107b2c525a36e54d41d879268fd2fcab9255a2b29723.img.xz",
"hash": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", "hash": "98e0642e2af77596e64d107b2c525a36e54d41d879268fd2fcab9255a2b29723",
"hash_raw": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", "hash_raw": "98e0642e2af77596e64d107b2c525a36e54d41d879268fd2fcab9255a2b29723",
"size": 3282256, "size": 3282256,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "ed61a650bea0c56652dd0fc68465d8fc722a4e6489dc8f257630c42c6adcdc89" "ondevice_hash": "907c705f72ebcbd3030e03da9ef4c65a3d599e056a79aa9e7c369fdff8e54dc4"
}, },
{ {
"name": "xbl_config", "name": "xbl_config",
"url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-4d8add65e80b3e5ca49a64fac76025ee3a57a1523abd9caa407aa8c5fb721b0f.img.xz",
"hash": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", "hash": "4d8add65e80b3e5ca49a64fac76025ee3a57a1523abd9caa407aa8c5fb721b0f",
"hash_raw": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", "hash_raw": "4d8add65e80b3e5ca49a64fac76025ee3a57a1523abd9caa407aa8c5fb721b0f",
"size": 98124, "size": 98124,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "b12801ffaa81e58e3cef914488d3b447e35483ba549b28c6cd9deb4814c3265f" "ondevice_hash": "46c472f52fb97a4836d08d0e790f5c8512651f520ce004bc3bbc6a143fc7a3c2"
}, },
{ {
"name": "abl", "name": "abl",
@ -163,14 +163,14 @@
}, },
{ {
"name": "aop", "name": "aop",
"url": "https://commadist.azureedge.net/agnosupdate/aop-21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/aop-d8add1d4c1b6b443debf7bb80040e88a12140d248a328650d65ceaa0df04c1b7.img.xz",
"hash": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", "hash": "d8add1d4c1b6b443debf7bb80040e88a12140d248a328650d65ceaa0df04c1b7",
"hash_raw": "21370172e590bd4ea907a558bcd6df20dc7a6c7d38b8e62fdde18f4a512ba9e9", "hash_raw": "d8add1d4c1b6b443debf7bb80040e88a12140d248a328650d65ceaa0df04c1b7",
"size": 184364, "size": 184364,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "c1be2f4aac5b3af49b904b027faec418d05efd7bd5144eb4fdfcba602bcf2180" "ondevice_hash": "e320da0d3f73aa09277a8be740c59f9cc605d2098b46a842c93ea2ac0ac97cb0"
}, },
{ {
"name": "bluetooth", "name": "bluetooth",
@ -207,14 +207,14 @@
}, },
{ {
"name": "devcfg", "name": "devcfg",
"url": "https://commadist.azureedge.net/agnosupdate/devcfg-d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/devcfg-7e8a836cf75a9097b1c78960d36f883699fcc3858d8a1d28338f889f6af25cc8.img.xz",
"hash": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", "hash": "7e8a836cf75a9097b1c78960d36f883699fcc3858d8a1d28338f889f6af25cc8",
"hash_raw": "d7d7e52963bbedbbf8a7e66847579ca106a0a729ce2cf60f4b8d8ea4b535d620", "hash_raw": "7e8a836cf75a9097b1c78960d36f883699fcc3858d8a1d28338f889f6af25cc8",
"size": 40336, "size": 40336,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "17b229668b20305ff8fa3cd5f94716a3aaa1e5bf9d1c24117eff7f2f81ae719f" "ondevice_hash": "7e9412d154036216e56c2346d24455dd45f56d6de4c9e8837597f22d59c83d93"
}, },
{ {
"name": "devinfo", "name": "devinfo",
@ -339,62 +339,62 @@
}, },
{ {
"name": "boot", "name": "boot",
"url": "https://commadist.azureedge.net/agnosupdate/boot-b96882012ab6cddda04f440009c798a6cff65977f984b12072e89afa592d86cb.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/boot-08291eb52a9d54b77e191ea1a78addf24aae28e15306ac3118d03ac9be29fbe9.img.xz",
"hash": "b96882012ab6cddda04f440009c798a6cff65977f984b12072e89afa592d86cb", "hash": "08291eb52a9d54b77e191ea1a78addf24aae28e15306ac3118d03ac9be29fbe9",
"hash_raw": "b96882012ab6cddda04f440009c798a6cff65977f984b12072e89afa592d86cb", "hash_raw": "08291eb52a9d54b77e191ea1a78addf24aae28e15306ac3118d03ac9be29fbe9",
"size": 17442816, "size": 17868800,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "8ed6c2796be5c5b29d64e6413b8e878d5bd1a3981d15216d2b5e84140cc4ea2a" "ondevice_hash": "18fab2e1eb2e43e5c39e20ee20e0d391586de528df6dbfdab6dabcdab835ee3e"
}, },
{ {
"name": "system", "name": "system",
"url": "https://commadist.azureedge.net/agnosupdate/system-2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/system-1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b.img.xz",
"hash": "325414e5c9f7516b2bf0fedb6abe6682f717897a6d84ab70d5afe91a59f244e9", "hash": "8d4b4dd80a8a537adf82faa07928066bec4568eae73bdcf4a5f0da94fb77b485",
"hash_raw": "2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc", "hash_raw": "1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b",
"size": 4718592000, "size": 5368709120,
"sparse": true, "sparse": true,
"full_check": false, "full_check": false,
"has_ab": true, "has_ab": true,
"ondevice_hash": "79f4f6d0b5b4a416f0f31261b430943a78e37c26d0e226e0ef412fe0eae3c727", "ondevice_hash": "a9569b9286fba882be003f9710383ae6de229a72db936e80be08dbd2c23f320e",
"alt": { "alt": {
"hash": "2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc", "hash": "1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b",
"url": "https://commadist.azureedge.net/agnosupdate/system-2b1bb223bf2100376ad5d543bfa4a483f33327b3478ec20ab36048388472c4bc.img", "url": "https://commadist.azureedge.net/agnosupdate/system-1a653b2a2006eb19017b9f091928a51fbb0b91c1ab218971779936892c9bd71b.img",
"size": 4718592000 "size": 5368709120
} }
}, },
{ {
"name": "userdata_90", "name": "userdata_90",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_90-b3112984d2a8534a83d2ce43d35efdd10c7d163d9699f611f0f72ad9e9cb5af9.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-a154dec5ebad07f63ebef989a1f7e44c449b9fb94b1048157d426ff0e78feef8.img.xz",
"hash": "bea163e6fb6ac6224c7f32619affb5afb834cd859971b0cab6d8297dd0098f0a", "hash": "32ef650ba25cbf867eb4699096e33027aa0ab79e05de2d1dfee3601b00b4fdf6",
"hash_raw": "b3112984d2a8534a83d2ce43d35efdd10c7d163d9699f611f0f72ad9e9cb5af9", "hash_raw": "a154dec5ebad07f63ebef989a1f7e44c449b9fb94b1048157d426ff0e78feef8",
"size": 96636764160, "size": 96636764160,
"sparse": true, "sparse": true,
"full_check": true, "full_check": true,
"has_ab": false, "has_ab": false,
"ondevice_hash": "f4841c6ae3207197886e5efbd50f44cc24822680d7b785fa2d2743c657f23287" "ondevice_hash": "9f21158f9055983c237d47a8eea8e27e978b5f25383756a7a9363a7bd9f7f72e"
}, },
{ {
"name": "userdata_89", "name": "userdata_89",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_89-3e63f670e4270474cec96f4da9250ee4e87e3106b0b043b7e82371e1c761e167.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-31ebdff72d44d3f60bdf0920e39171795494c275b8cff023cf23ec592af7a4b3.img.xz",
"hash": "b5458a29dd7d4a4c9b7ad77b8baa5f804142ac78d97c6668839bf2a650e32518", "hash": "a62837b235be14b257baf05ddc6bddd026c8859bbb4f154d0323c7efa58cb938",
"hash_raw": "3e63f670e4270474cec96f4da9250ee4e87e3106b0b043b7e82371e1c761e167", "hash_raw": "31ebdff72d44d3f60bdf0920e39171795494c275b8cff023cf23ec592af7a4b3",
"size": 95563022336, "size": 95563022336,
"sparse": true, "sparse": true,
"full_check": true, "full_check": true,
"has_ab": false, "has_ab": false,
"ondevice_hash": "1dc10c542d3b019258fc08dc7dfdb49d9abad065e46d030b89bc1a2e0197f526" "ondevice_hash": "a5caa169c840de6d1804b4186a1d26486be95e1837c4df16ec45952665356942"
}, },
{ {
"name": "userdata_30", "name": "userdata_30",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_30-1d3885d4370974e55f0c6f567fd0344fc5ee10db067aa5810fbaf402eadb032c.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/userdata_30-16518389a1ed7ad6277dbab75d18aa13833fb4ed4010f456438f2c2ac8c61140.img.xz",
"hash": "687d178cfc91be5d7e8aa1333405b610fdce01775b8333bd0985b81642b94eea", "hash": "cb8c2fc2ae83cacb86af4ce96c6d61e4bd3cd2591e612e12878c27fa51030ffa",
"hash_raw": "1d3885d4370974e55f0c6f567fd0344fc5ee10db067aa5810fbaf402eadb032c", "hash_raw": "16518389a1ed7ad6277dbab75d18aa13833fb4ed4010f456438f2c2ac8c61140",
"size": 32212254720, "size": 32212254720,
"sparse": true, "sparse": true,
"full_check": true, "full_check": true,
"has_ab": false, "has_ab": false,
"ondevice_hash": "9ddbd1dae6ee7dc919f018364cf2f29dad138c9203c5a49aea0cbb9bf2e137e5" "ondevice_hash": "5dd8e1f87a3f985ece80f7a36da1cbdabd77bcc11d26fc7bb85540069eff8ead"
} }
] ]

@ -1,3 +1,17 @@
version https://git-lfs.github.com/spec/v1 #!/usr/bin/env bash
oid sha256:eba5f44e6a763e1f74d1c718993218adcc72cba4caafe99b595fa701151a4c54
size 10448792 DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"
AGNOS_PY=$1
MANIFEST=$2
if [[ ! -f "$AGNOS_PY" || ! -f "$MANIFEST" ]]; then
echo "invalid args"
exit 1
fi
if systemctl is-active --quiet weston-ready; then
$DIR/updater_weston $AGNOS_PY $MANIFEST
else
$DIR/updater_magic $AGNOS_PY $MANIFEST
fi

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:ffc9893e48b10096062f5fd1a14016addf7adb969f20f31ff26e68579992283c
size 20780744

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:eba5f44e6a763e1f74d1c718993218adcc72cba4caafe99b595fa701151a4c54
size 10448792

@ -1,5 +1,6 @@
#pragma once #pragma once
#include <cstdlib>
#include <vector> #include <vector>
#include "cereal/messaging/messaging.h" #include "cereal/messaging/messaging.h"
@ -46,7 +47,8 @@ struct EncoderSettings {
} }
static EncoderSettings StreamEncoderSettings() { static EncoderSettings StreamEncoderSettings() {
return EncoderSettings{.encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .bitrate = 1'000'000, .gop_size = 15}; int _stream_bitrate = getenv("STREAM_BITRATE") ? atoi(getenv("STREAM_BITRATE")) : 1'000'000;
return EncoderSettings{.encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .bitrate = _stream_bitrate , .gop_size = 15};
} }
}; };

@ -29,7 +29,7 @@ MAX_UPLOAD_SIZES = {
"qcam": 5*1e6, "qcam": 5*1e6,
} }
allow_sleep = bool(os.getenv("UPLOADER_SLEEP", "1")) allow_sleep = bool(int(os.getenv("UPLOADER_SLEEP", "1")))
force_wifi = os.getenv("FORCEWIFI") is not None force_wifi = os.getenv("FORCEWIFI") is not None
fake_upload = os.getenv("FAKEUPLOAD") is not None fake_upload = os.getenv("FAKEUPLOAD") is not None

@ -14,7 +14,7 @@ from openpilot.system.version import get_build_metadata
MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9
CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache")
TOTAL_SCONS_NODES = 3275 TOTAL_SCONS_NODES = 2280
MAX_BUILD_PROGRESS = 100 MAX_BUILD_PROGRESS = 100
def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None:

@ -80,8 +80,8 @@ procs = [
PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(WEBCAM or not PC)), PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(WEBCAM or not PC)),
PythonProcess("sensord", "system.sensord.sensord", only_onroad, enabled=not PC), PythonProcess("sensord", "system.sensord.sensord", only_onroad, enabled=not PC),
NativeProcess("ui", "selfdrive/ui", ["./ui"], always_run, watchdog_max_dt=(5 if not PC else None)), # NativeProcess("ui", "selfdrive/ui", ["./ui"], always_run, enabled=False, watchdog_max_dt=(5 if not PC else None)),
PythonProcess("raylib_ui", "selfdrive.ui.ui", always_run, enabled=False, watchdog_max_dt=(5 if not PC else None)), PythonProcess("ui", "selfdrive.ui.ui", always_run),
PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad), PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad),
PythonProcess("locationd", "selfdrive.locationd.locationd", only_onroad), PythonProcess("locationd", "selfdrive.locationd.locationd", only_onroad),
NativeProcess("_pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), NativeProcess("_pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False),

@ -2,6 +2,8 @@ import atexit
import cffi import cffi
import os import os
import time import time
import signal
import sys
import pyray as rl import pyray as rl
import threading import threading
from collections.abc import Callable from collections.abc import Callable
@ -11,10 +13,10 @@ from enum import StrEnum
from typing import NamedTuple from typing import NamedTuple
from importlib.resources import as_file, files from importlib.resources import as_file, files
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.system.hardware import HARDWARE, PC from openpilot.system.hardware import HARDWARE, PC, TICI
from openpilot.common.realtime import Ratekeeper from openpilot.common.realtime import Ratekeeper
_DEFAULT_FPS = int(os.getenv("FPS", "60")) _DEFAULT_FPS = int(os.getenv("FPS", 20 if TICI else 60))
FPS_LOG_INTERVAL = 5 # Seconds between logging FPS drops FPS_LOG_INTERVAL = 5 # Seconds between logging FPS drops
FPS_DROP_THRESHOLD = 0.9 # FPS drop threshold for triggering a warning FPS_DROP_THRESHOLD = 0.9 # FPS drop threshold for triggering a warning
FPS_CRITICAL_THRESHOLD = 0.5 # Critical threshold for triggering strict actions FPS_CRITICAL_THRESHOLD = 0.5 # Critical threshold for triggering strict actions
@ -30,6 +32,10 @@ SCALE = float(os.getenv("SCALE", "1.0"))
DEFAULT_TEXT_SIZE = 60 DEFAULT_TEXT_SIZE = 60
DEFAULT_TEXT_COLOR = rl.WHITE DEFAULT_TEXT_COLOR = rl.WHITE
# Qt draws fonts accounting for ascent/descent differently, so compensate to match old styles
# The real scales for the fonts below range from 1.212 to 1.266
FONT_SCALE = 1.242
ASSETS_DIR = files("openpilot.selfdrive").joinpath("assets") ASSETS_DIR = files("openpilot.selfdrive").joinpath("assets")
FONT_DIR = ASSETS_DIR.joinpath("fonts") FONT_DIR = ASSETS_DIR.joinpath("fonts")
@ -72,7 +78,7 @@ class MouseState:
self._events: deque[MouseEvent] = deque(maxlen=MOUSE_THREAD_RATE) # bound event list self._events: deque[MouseEvent] = deque(maxlen=MOUSE_THREAD_RATE) # bound event list
self._prev_mouse_event: list[MouseEvent | None] = [None] * MAX_TOUCH_SLOTS self._prev_mouse_event: list[MouseEvent | None] = [None] * MAX_TOUCH_SLOTS
self._rk = Ratekeeper(MOUSE_THREAD_RATE) self._rk = Ratekeeper(MOUSE_THREAD_RATE, print_delay_threshold=None)
self._lock = threading.Lock() self._lock = threading.Lock()
self._exit_event = threading.Event() self._exit_event = threading.Event()
self._thread = None self._thread = None
@ -108,8 +114,8 @@ class MouseState:
ev = MouseEvent( ev = MouseEvent(
MousePos(x, y), MousePos(x, y),
slot, slot,
rl.is_mouse_button_pressed(slot), rl.is_mouse_button_pressed(slot), # noqa: TID251
rl.is_mouse_button_released(slot), rl.is_mouse_button_released(slot), # noqa: TID251
rl.is_mouse_button_down(slot), rl.is_mouse_button_down(slot),
time.monotonic(), time.monotonic(),
) )
@ -142,17 +148,25 @@ class GuiApplication:
# Debug variables # Debug variables
self._mouse_history: deque[MousePos] = deque(maxlen=MOUSE_THREAD_RATE) self._mouse_history: deque[MousePos] = deque(maxlen=MOUSE_THREAD_RATE)
@property
def target_fps(self):
return self._target_fps
def request_close(self): def request_close(self):
self._window_close_requested = True self._window_close_requested = True
def init_window(self, title: str, fps: int = _DEFAULT_FPS): def init_window(self, title: str, fps: int = _DEFAULT_FPS):
atexit.register(self.close) # Automatically call close() on exit def _close(sig, frame):
self.close()
sys.exit(0)
signal.signal(signal.SIGINT, _close)
atexit.register(self.close)
HARDWARE.set_display_power(True) HARDWARE.set_display_power(True)
HARDWARE.set_screen_brightness(65) HARDWARE.set_screen_brightness(65)
self._set_log_callback() self._set_log_callback()
rl.set_trace_log_level(rl.TraceLogLevel.LOG_ALL) rl.set_trace_log_level(rl.TraceLogLevel.LOG_WARNING)
flags = rl.ConfigFlags.FLAG_MSAA_4X_HINT flags = rl.ConfigFlags.FLAG_MSAA_4X_HINT
if ENABLE_VSYNC: if ENABLE_VSYNC:
@ -164,59 +178,64 @@ class GuiApplication:
rl.set_mouse_scale(1 / self._scale, 1 / self._scale) rl.set_mouse_scale(1 / self._scale, 1 / self._scale)
self._render_texture = rl.load_render_texture(self._width, self._height) self._render_texture = rl.load_render_texture(self._width, self._height)
rl.set_texture_filter(self._render_texture.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) rl.set_texture_filter(self._render_texture.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR)
rl.set_target_fps(fps)
self.set_target_fps(fps) self._target_fps = fps
self._set_styles() self._set_styles()
self._load_fonts() self._load_fonts()
self._patch_text_functions()
if not PC: if not PC:
self._mouse.start() self._mouse.start()
@property
def target_fps(self):
return self._target_fps
def set_target_fps(self, fps: int):
self._target_fps = fps
rl.set_target_fps(fps)
def set_modal_overlay(self, overlay, callback: Callable | None = None): def set_modal_overlay(self, overlay, callback: Callable | None = None):
if self._modal_overlay.overlay is not None:
if self._modal_overlay.callback is not None:
self._modal_overlay.callback(-1)
self._modal_overlay = ModalOverlay(overlay=overlay, callback=callback) self._modal_overlay = ModalOverlay(overlay=overlay, callback=callback)
def texture(self, asset_path: str, width: int, height: int, alpha_premultiply=False, keep_aspect_ratio=True): def texture(self, asset_path: str, width: int | None = None, height: int | None = None,
alpha_premultiply=False, keep_aspect_ratio=True):
cache_key = f"{asset_path}_{width}_{height}_{alpha_premultiply}{keep_aspect_ratio}" cache_key = f"{asset_path}_{width}_{height}_{alpha_premultiply}{keep_aspect_ratio}"
if cache_key in self._textures: if cache_key in self._textures:
return self._textures[cache_key] return self._textures[cache_key]
with as_file(ASSETS_DIR.joinpath(asset_path)) as fspath: with as_file(ASSETS_DIR.joinpath(asset_path)) as fspath:
texture_obj = self._load_texture_from_image(fspath.as_posix(), width, height, alpha_premultiply, keep_aspect_ratio) image_obj = self._load_image_from_path(fspath.as_posix(), width, height, alpha_premultiply, keep_aspect_ratio)
texture_obj = self._load_texture_from_image(image_obj)
self._textures[cache_key] = texture_obj self._textures[cache_key] = texture_obj
return texture_obj return texture_obj
def _load_texture_from_image(self, image_path: str, width: int, height: int, alpha_premultiply=False, keep_aspect_ratio=True): def _load_image_from_path(self, image_path: str, width: int | None = None, height: int | None = None,
"""Load and resize a texture, storing it for later automatic unloading.""" alpha_premultiply: bool = False, keep_aspect_ratio: bool = True) -> rl.Image:
"""Load and resize an image, storing it for later automatic unloading."""
image = rl.load_image(image_path) image = rl.load_image(image_path)
if alpha_premultiply: if alpha_premultiply:
rl.image_alpha_premultiply(image) rl.image_alpha_premultiply(image)
# Resize with aspect ratio preservation if requested if width is not None and height is not None:
if keep_aspect_ratio: # Resize with aspect ratio preservation if requested
orig_width = image.width if keep_aspect_ratio:
orig_height = image.height orig_width = image.width
orig_height = image.height
scale_width = width / orig_width scale_width = width / orig_width
scale_height = height / orig_height scale_height = height / orig_height
# Calculate new dimensions # Calculate new dimensions
scale = min(scale_width, scale_height) scale = min(scale_width, scale_height)
new_width = int(orig_width * scale) new_width = int(orig_width * scale)
new_height = int(orig_height * scale) new_height = int(orig_height * scale)
rl.image_resize(image, new_width, new_height) rl.image_resize(image, new_width, new_height)
else: else:
rl.image_resize(image, width, height) rl.image_resize(image, width, height)
return image
def _load_texture_from_image(self, image: rl.Image) -> rl.Texture:
"""Send image to GPU and unload original image."""
texture = rl.load_texture_from_image(image) texture = rl.load_texture_from_image(image)
# Set texture filtering to smooth the result # Set texture filtering to smooth the result
rl.set_texture_filter(texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) rl.set_texture_filter(texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR)
@ -334,7 +353,7 @@ class GuiApplication:
for layout in KEYBOARD_LAYOUTS.values(): for layout in KEYBOARD_LAYOUTS.values():
all_chars.update(key for row in layout for key in row) all_chars.update(key for row in layout for key in row)
all_chars = "".join(all_chars) all_chars = "".join(all_chars)
all_chars += "–✓×°" all_chars += "–✓×°§•"
codepoint_count = rl.ffi.new("int *", 1) codepoint_count = rl.ffi.new("int *", 1)
codepoints = rl.load_codepoints(all_chars, codepoint_count) codepoints = rl.load_codepoints(all_chars, codepoint_count)
@ -355,6 +374,16 @@ class GuiApplication:
rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiControlProperty.TEXT_COLOR_NORMAL, rl.color_to_int(DEFAULT_TEXT_COLOR)) rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiControlProperty.TEXT_COLOR_NORMAL, rl.color_to_int(DEFAULT_TEXT_COLOR))
rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiControlProperty.BASE_COLOR_NORMAL, rl.color_to_int(rl.Color(50, 50, 50, 255))) rl.gui_set_style(rl.GuiControl.DEFAULT, rl.GuiControlProperty.BASE_COLOR_NORMAL, rl.color_to_int(rl.Color(50, 50, 50, 255)))
def _patch_text_functions(self):
# Wrap pyray text APIs to apply a global text size scale so our px sizes match Qt
if not hasattr(rl, "_orig_draw_text_ex"):
rl._orig_draw_text_ex = rl.draw_text_ex
def _draw_text_ex_scaled(font, text, position, font_size, spacing, tint):
return rl._orig_draw_text_ex(font, text, position, font_size * FONT_SCALE, spacing, tint)
rl.draw_text_ex = _draw_text_ex_scaled
def _set_log_callback(self): def _set_log_callback(self):
ffi_libc = cffi.FFI() ffi_libc = cffi.FFI()
ffi_libc.cdef(""" ffi_libc.cdef("""

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save