diff --git a/.github/workflows/ci_weekly_report.yaml b/.github/workflows/ci_weekly_report.yaml index b96a5a56a8..1d3563fb18 100644 --- a/.github/workflows/ci_weekly_report.yaml +++ b/.github/workflows/ci_weekly_report.yaml @@ -38,7 +38,7 @@ jobs: report: needs: [ci_matrix_run] runs-on: ubuntu-latest - if: always() + if: always() && github.repository == 'commaai/openpilot' steps: - name: Get job results uses: actions/github-script@v7 diff --git a/.github/workflows/mici_raylib_ui_preview.yaml b/.github/workflows/mici_raylib_ui_preview.yaml new file mode 100644 index 0000000000..707825b1ac --- /dev/null +++ b/.github/workflows/mici_raylib_ui_preview.yaml @@ -0,0 +1,151 @@ +name: "mici raylib ui preview" +on: + push: + branches: + - master + pull_request_target: + types: [assigned, opened, synchronize, reopened, edited] + branches: + - 'master' + paths: + - 'selfdrive/assets/**' + - 'selfdrive/ui/**' + - 'system/ui/**' + workflow_dispatch: + +env: + UI_JOB_NAME: "Create mici raylib UI Report" + REPORT_NAME: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} + SHA: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && github.sha || github.event.pull_request.head.sha }} + BRANCH_NAME: "openpilot/pr-${{ github.event.number }}-mici-raylib-ui" + MASTER_BRANCH_NAME: "openpilot_master_ui_mici_raylib" + # All report files are pushed here + REPORT_FILES_BRANCH_NAME: "mici-raylib-ui-reports" + +jobs: + preview: + if: github.repository == 'commaai/openpilot' + name: preview + runs-on: ubuntu-latest + timeout-minutes: 20 + permissions: + contents: read + pull-requests: write + actions: read + steps: + - uses: actions/checkout@v4 + with: + submodules: true + + - name: Waiting for ui generation to end + uses: lewagon/wait-on-check-action@v1.3.4 + with: + ref: ${{ env.SHA }} + check-name: ${{ env.UI_JOB_NAME }} + repo-token: ${{ secrets.GITHUB_TOKEN }} + allowed-conclusions: success + wait-interval: 20 + + - name: Getting workflow run ID + id: get_run_id + run: | + echo "run_id=$(curl https://api.github.com/repos/${{ github.repository }}/commits/${{ env.SHA }}/check-runs | jq -r '.check_runs[] | select(.name == "${{ env.UI_JOB_NAME }}") | .html_url | capture("(?[0-9]+)") | .number')" >> $GITHUB_OUTPUT + + - name: Getting proposed ui # filename: pr_ui/mici_ui_replay.mp4 + id: download-artifact + uses: dawidd6/action-download-artifact@v6 + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + run_id: ${{ steps.get_run_id.outputs.run_id }} + search_artifacts: true + name: mici-raylib-report-1-${{ env.REPORT_NAME }} + path: ${{ github.workspace }}/pr_ui + + - name: Getting master ui # filename: master_ui_raylib/mici_ui_replay.mp4 + uses: actions/checkout@v4 + with: + repository: commaai/ci-artifacts + ssh-key: ${{ secrets.CI_ARTIFACTS_DEPLOY_KEY }} + path: ${{ github.workspace }}/master_ui_raylib + ref: ${{ env.MASTER_BRANCH_NAME }} + + - name: Saving new master ui + if: github.ref == 'refs/heads/master' && github.event_name == 'push' + working-directory: ${{ github.workspace }}/master_ui_raylib + run: | + git checkout --orphan=new_master_ui_mici_raylib + git rm -rf * + git branch -D ${{ env.MASTER_BRANCH_NAME }} + git branch -m ${{ env.MASTER_BRANCH_NAME }} + git config user.name "GitHub Actions Bot" + git config user.email "<>" + mv ${{ github.workspace }}/pr_ui/* . + git add . + git commit -m "mici raylib video for commit ${{ env.SHA }}" + git push origin ${{ env.MASTER_BRANCH_NAME }} --force + + - name: Setup FFmpeg + uses: AnimMouse/setup-ffmpeg@ae28d57dabbb148eff63170b6bf7f2b60062cbae + + - name: Finding diff + if: github.event_name == 'pull_request_target' + id: find_diff + run: | + # Find the video file from PR + pr_video="${{ github.workspace }}/pr_ui/mici_ui_replay_proposed.mp4" + mv "${{ github.workspace }}/pr_ui/mici_ui_replay.mp4" "$pr_video" + + master_video="${{ github.workspace }}/pr_ui/mici_ui_replay_master.mp4" + mv "${{ github.workspace }}/master_ui_raylib/mici_ui_replay.mp4" "$master_video" + + # Run report + export PYTHONPATH=${{ github.workspace }} + baseurl="https://github.com/commaai/ci-artifacts/raw/refs/heads/${{ env.BRANCH_NAME }}" + diff_exit_code=0 + python3 ${{ github.workspace }}/selfdrive/ui/tests/diff/diff.py "${{ github.workspace }}/pr_ui/mici_ui_replay_master.mp4" "${{ github.workspace }}/pr_ui/mici_ui_replay_proposed.mp4" "diff.html" --basedir "$baseurl" --no-open || diff_exit_code=$? + + # Copy diff report files + cp ${{ github.workspace }}/selfdrive/ui/tests/diff/report/diff.html ${{ github.workspace }}/pr_ui/ + cp ${{ github.workspace }}/selfdrive/ui/tests/diff/report/diff.mp4 ${{ github.workspace }}/pr_ui/ + + REPORT_URL="https://commaai.github.io/ci-artifacts/diff_pr_${{ github.event.number }}.html" + if [ $diff_exit_code -eq 0 ]; then + DIFF="✅ Videos are identical! [View Diff Report]($REPORT_URL)" + else + DIFF="❌ Videos differ! [View Diff Report]($REPORT_URL)" + fi + echo "DIFF=$DIFF" >> "$GITHUB_OUTPUT" + + - name: Saving proposed ui + if: github.event_name == 'pull_request_target' + working-directory: ${{ github.workspace }}/master_ui_raylib + run: | + # Overwrite PR branch w/ proposed ui, and master ui at this point in time for future reference + git config user.name "GitHub Actions Bot" + git config user.email "<>" + git checkout --orphan=${{ env.BRANCH_NAME }} + git rm -rf * + mv ${{ github.workspace }}/pr_ui/* . + git add . + git commit -m "mici raylib video for PR #${{ github.event.number }}" + git push origin ${{ env.BRANCH_NAME }} --force + + # Append diff report to report files branch + git fetch origin ${{ env.REPORT_FILES_BRANCH_NAME }} + git checkout ${{ env.REPORT_FILES_BRANCH_NAME }} + cp ${{ github.workspace }}/selfdrive/ui/tests/diff/report/diff.html diff_pr_${{ github.event.number }}.html + git add diff_pr_${{ github.event.number }}.html + git commit -m "mici raylib ui diff report for PR #${{ github.event.number }}" || echo "No changes to commit" + git push origin ${{ env.REPORT_FILES_BRANCH_NAME }} + + - name: Comment Video on PR + if: github.event_name == 'pull_request_target' + uses: thollander/actions-comment-pull-request@v2 + with: + message: | + + ## mici raylib UI Preview + ${{ steps.find_diff.outputs.DIFF }} + comment_tag: run_id_video_mici_raylib + pr_number: ${{ github.event.number }} + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} diff --git a/.github/workflows/tests.yaml b/.github/workflows/tests.yaml index aab16ffbbe..38bb7435e2 100644 --- a/.github/workflows/tests.yaml +++ b/.github/workflows/tests.yaml @@ -297,3 +297,29 @@ jobs: with: name: raylib-report-${{ inputs.run_number || '1' }}-${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} path: selfdrive/ui/tests/test_ui/raylib_report/screenshots + + create_mici_raylib_ui_report: + name: Create mici raylib UI Report + runs-on: ${{ + (github.repository == 'commaai/openpilot') && + ((github.event_name != 'pull_request') || + (github.event.pull_request.head.repo.full_name == 'commaai/openpilot')) + && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') + || fromJSON('["ubuntu-24.04"]') }} + steps: + - uses: actions/checkout@v4 + with: + submodules: true + - uses: ./.github/workflows/setup-with-retry + - name: Build openpilot + run: ${{ env.RUN }} "scons -j$(nproc)" + - name: Create mici raylib UI Report + run: > + ${{ env.RUN }} "PYTHONWARNINGS=ignore && + source selfdrive/test/setup_xvfb.sh && + WINDOWED=1 python3 selfdrive/ui/tests/diff/replay.py" + - name: Upload Raylib UI Report + uses: actions/upload-artifact@v4 + with: + name: mici-raylib-report-${{ inputs.run_number || '1' }}-${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} + path: selfdrive/ui/tests/diff/report diff --git a/RELEASES.md b/RELEASES.md index 58044dc694..fabe635c71 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,6 @@ +Version 0.10.3 (2025-12-10) +======================== + Version 0.10.2 (2025-11-19) ======================== * comma four support diff --git a/common/api/__init__.py b/common/api/__init__.py index 8b261486ba..d0b3dbc9e9 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -22,5 +22,5 @@ def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): return CommaConnectApi(None).api_get(endpoint, method, timeout, access_token, **params) -def get_key_pair(): +def get_key_pair() -> tuple[str, str, str] | tuple[None, None, None]: return CommaConnectApi(None).get_key_pair() diff --git a/common/api/base.py b/common/api/base.py index 682b266056..c37652b455 100644 --- a/common/api/base.py +++ b/common/api/base.py @@ -6,9 +6,9 @@ from datetime import datetime, timedelta, UTC from openpilot.system.hardware.hw import Paths from openpilot.system.version import get_version - # name : jwt signature algorithm -KEYS = {"id_rsa" : "RS256", - "id_ecdsa" : "ES256"} +# name: jwt signature algorithm +KEYS = {"id_rsa": "RS256", + "id_ecdsa": "ES256"} class BaseApi: @@ -62,7 +62,7 @@ class BaseApi: return requests.request(method, f"{self.api_host}/{endpoint}", timeout=timeout, headers=headers, json=json, params=params) @staticmethod - def get_key_pair(): + def get_key_pair() -> tuple[str, str, str] | tuple[None, None, None]: for key in KEYS: if os.path.isfile(Paths.persist_root() + f'/comma/{key}') and os.path.isfile(Paths.persist_root() + f'/comma/{key}.pub'): with open(Paths.persist_root() + f'/comma/{key}') as private, open(Paths.persist_root() + f'/comma/{key}.pub') as public: diff --git a/common/model.h b/common/model.h index 03773b633a..f01460cdb6 100644 --- a/common/model.h +++ b/common/model.h @@ -1 +1 @@ -#define DEFAULT_MODEL "The Cool People (Default)" +#define DEFAULT_MODEL "Dark Souls 2 (Default)" diff --git a/common/params_keys.h b/common/params_keys.h index 38578d7ddc..a5f0ae29f2 100644 --- a/common/params_keys.h +++ b/common/params_keys.h @@ -71,6 +71,7 @@ inline static std::unordered_map keys = { {"LastGPSPosition", {PERSISTENT, STRING}}, {"LastManagerExitReason", {CLEAR_ON_MANAGER_START, STRING}}, {"LastOffroadStatusPacket", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, JSON}}, + {"LastAgnosPowerMonitorShutdown", {CLEAR_ON_MANAGER_START, STRING}}, {"LastPowerDropDetected", {CLEAR_ON_MANAGER_START, STRING}}, {"LastUpdateException", {CLEAR_ON_MANAGER_START, STRING}}, {"LastUpdateRouteCount", {PERSISTENT, INT, "0"}}, diff --git a/common/tests/test_file_helpers.py b/common/tests/test_file_helpers.py index c7fe1984c5..c2b880f873 100644 --- a/common/tests/test_file_helpers.py +++ b/common/tests/test_file_helpers.py @@ -1,7 +1,7 @@ import os from uuid import uuid4 -from openpilot.common.utils import atomic_write_in_dir +from openpilot.common.utils import atomic_write class TestFileHelpers: @@ -15,5 +15,5 @@ class TestFileHelpers: assert f.read() == "test" os.remove(path) - def test_atomic_write_in_dir(self): - self.run_atomic_write_func(atomic_write_in_dir) + def test_atomic_write(self): + self.run_atomic_write_func(atomic_write) diff --git a/common/utils.py b/common/utils.py index 89c0601f06..71b29a0c4e 100644 --- a/common/utils.py +++ b/common/utils.py @@ -32,8 +32,8 @@ class CallbackReader: @contextlib.contextmanager -def atomic_write_in_dir(path: str, mode: str = 'w', buffering: int = -1, encoding: str | None = None, newline: str | None = None, - overwrite: bool = False): +def atomic_write(path: str, mode: str = 'w', buffering: int = -1, encoding: str | None = None, newline: str | None = None, + overwrite: bool = False): """Write to a file atomically using a temporary file in the same directory as the destination file.""" dir_name = os.path.dirname(path) diff --git a/common/version.h b/common/version.h index ef20670781..c489ecc578 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.10.2" +#define COMMA_VERSION "0.10.3" diff --git a/docs/CARS.md b/docs/CARS.md index 4c1e90e18d..b36c11aef2 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -20,7 +20,7 @@ A supported vehicle is one that just works when you install a comma device. All |Audi|Q3 2019-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,15](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma four
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
Buy Here
||| |Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,15](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma four
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
Buy Here
||| |Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,15](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma four
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
Buy Here
||| -|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 harness box
- 1 mount
Buy Here
||| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim, without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 harness box
- 1 mount
Buy Here
||| |Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 harness box
- 1 mount
Buy Here
||| |Chevrolet|Bolt EV Non-ACC 2017|Adaptive Cruise Control (ACC)|Stock|24 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 harness box
- 1 mount
Buy Here
||| |Chevrolet|Bolt EV Non-ACC 2018-21|Adaptive Cruise Control (ACC)|Stock|24 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 harness box
- 1 mount
Buy Here
||| @@ -384,7 +384,7 @@ If your car has the following packages or features, then it's a good candidate f | Make | Required Package/Features | | ---- | ------------------------- | -| Acura | Any car with AcuraWatch Plus will work. AcuraWatch Plus comes standard on many newer models. | +| Acura | Any car with AcuraWatch will work. AcuraWatch comes standard on many newer models. | | Ford | Any car with Lane Centering will likely work. | | Honda | Any car with Honda Sensing will work. Honda Sensing comes standard on many newer models. | | Subaru | Any car with EyeSight will work. EyeSight comes standard on many newer models. | diff --git a/docs/how-to/turn-the-speed-blue.md b/docs/how-to/turn-the-speed-blue.md index eb6e75afa2..644c35e0ab 100644 --- a/docs/how-to/turn-the-speed-blue.md +++ b/docs/how-to/turn-the-speed-blue.md @@ -31,7 +31,7 @@ We'll run the `replay` tool with the demo route to get data streaming for testin tools/replay/replay --demo # in terminal 2 -selfdrive/ui/ui +./selfdrive/ui/ui.py ``` The openpilot UI should launch and show a replay of the demo route. @@ -43,39 +43,36 @@ If you have your own comma device, you can replace `--demo` with one of your own Now let’s update the speed display color in the UI. -Search for the function responsible for rendering UI text: +Search for the function responsible for rendering the current speed: ```bash -git grep "drawText" selfdrive/ui/qt/onroad/hud.cc +git grep "_draw_current_speed" selfdrive/ui/onroad/hud_renderer.py ``` -You’ll find the relevant code inside `selfdrive/ui/qt/onroad/hud.cc`, in this function: +You'll find the relevant code inside `selfdrive/ui/onroad/hud_renderer.py`, in this function: -```cpp -void HudRenderer::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { - QRect real_rect = p.fontMetrics().boundingRect(text); - real_rect.moveCenter({x, y - real_rect.height() / 2}); - - p.setPen(QColor(0xff, 0xff, 0xff, alpha)); // <- this sets the speed text color - p.drawText(real_rect.x(), real_rect.bottom(), text); -} +```python +def _draw_current_speed(self, rect: rl.Rectangle) -> None: + """Draw the current vehicle speed and unit.""" + speed_text = str(round(self.speed)) + speed_text_size = measure_text_cached(self._font_bold, speed_text, FONT_SIZES.current_speed) + 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) # <- this sets the speed text color ``` -Change the `QColor(...)` line to make it **blue** instead of white. A nice soft blue is `#8080FF`, which translates to: +Change `COLORS.white` to make it **blue** instead of white. A nice soft blue is `#8080FF`, which you can change inline: ```diff -- p.setPen(QColor(0xff, 0xff, 0xff, alpha)); -+ p.setPen(QColor(0x80, 0x80, 0xFF, alpha)); +- 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, rl.Color(0x80, 0x80, 0xFF, 255)) ``` -This change will tint all speed-related UI text to blue with the same transparency (`alpha`). - --- -## 4. Rebuild the UI +## 4. Re-run the UI -After making changes, rebuild Openpilot so your new UI is compiled: +After making changes, re-run the UI to see your new UI: ```bash -scons -j$(nproc) && selfdrive/ui/ui +./selfdrive/ui/ui.py ``` ![](https://blog.comma.ai/img/blue_speed_ui.png) diff --git a/opendbc_repo b/opendbc_repo index 61bf5a90c5..f746884333 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 61bf5a90c5c1917b657b8dd50c4d95e437413170 +Subproject commit f746884333eab1aa493e59bf83132e0617260a5f diff --git a/panda b/panda index dee9061b2a..5f3c09c910 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit dee9061b2ab83845b8620e8722620fcf50a316dd +Subproject commit 5f3c09c9105f26c6c5c858d5c7f4e375a367fcc1 diff --git a/pyproject.toml b/pyproject.toml index c58d950496..90feace27d 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -85,6 +85,7 @@ docs = [ ] testing = [ + "coverage", "hypothesis ==6.47.*", "mypy", "pytest", @@ -115,7 +116,7 @@ dev = [ "pyautogui", "pygame", "pyopencl; platform_machine != 'aarch64'", # broken on arm64 - "pytools < 2024.1.11; platform_machine != 'aarch64'", # pyopencl use a broken version + "pytools>=2025.1.6; platform_machine != 'aarch64'", "pywinctl", "pyprof2calltree", "tabulate", @@ -125,7 +126,7 @@ dev = [ tools = [ "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal-0.4.2.4/metadrive_simulator-0.4.2.4-py3-none-any.whl ; (platform_machine != 'aarch64')", - "dearpygui>=2.1.0", + "dearpygui>=2.1.0; (sys_platform != 'linux' or platform_machine != 'aarch64')", # not vended for linux aarch64 ] [project.urls] @@ -226,7 +227,7 @@ lint.select = [ "TRY203", "TRY400", "TRY401", # try/excepts "RUF008", "RUF100", "TID251", - "PLR1704", + "PLE", "PLR1704", ] lint.ignore = [ "E741", diff --git a/scripts/usbgpu/benchmark.sh b/scripts/usbgpu/benchmark.sh new file mode 100755 index 0000000000..04a76d054e --- /dev/null +++ b/scripts/usbgpu/benchmark.sh @@ -0,0 +1,26 @@ +#!/usr/bin/env bash +set -e + +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" +cd $DIR/../../tinygrad_repo + +GREEN='\033[0;32m' +NC='\033[0m' + + +#export DEBUG=2 +export PYTHONPATH=. +export AM_RESET=1 +export AMD=1 +export AMD_IFACE=USB +export AMD_LLVM=1 + +python3 -m unittest -q --buffer test.test_tiny.TestTiny.test_plus \ + > /tmp/test_tiny.log 2>&1 || (cat /tmp/test_tiny.log; exit 1) +printf "${GREEN}Booted in ${SECONDS}s${NC}\n" +printf "${GREEN}=============${NC}\n" + +printf "\n\n" +printf "${GREEN}Transfer speeds:${NC}\n" +printf "${GREEN}================${NC}\n" +python3 test/external/external_test_usb_asm24.py TestDevCopySpeeds diff --git a/selfdrive/assets/sounds/disengage.wav b/selfdrive/assets/sounds/disengage.wav index 8983884b25..7bfd97ad71 100644 --- a/selfdrive/assets/sounds/disengage.wav +++ b/selfdrive/assets/sounds/disengage.wav @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:c94582be9d921146b3c356e08a7352700c309cb407877c1180542811b2d637fa -size 48078 +oid sha256:42bd04a57b527c787a0555503e02a203f7d672c12d448769a3f41f17befbf013 +size 48044 diff --git a/selfdrive/assets/sounds/engage.wav b/selfdrive/assets/sounds/engage.wav index 39d4c749c8..8633b5ac2d 100644 --- a/selfdrive/assets/sounds/engage.wav +++ b/selfdrive/assets/sounds/engage.wav @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:bc2b12bfe816a79307660b6b3d2de87a7643c6ccbfc9d1b33804645ad717682a -size 48078 +oid sha256:b1e177499d9439367179cc57a6301b6162393972e3a136cc35c5fdac026bf10a +size 48044 diff --git a/selfdrive/assets/sounds/make_beeps.py b/selfdrive/assets/sounds/make_beeps.py new file mode 100644 index 0000000000..6161e80e74 --- /dev/null +++ b/selfdrive/assets/sounds/make_beeps.py @@ -0,0 +1,19 @@ +import numpy as np +from scipy.io import wavfile + + +sr = 48000 +max_int16 = 2**15 - 1 + +def harmonic_beep(freq, duration_seconds): + n_total = int(sr * duration_seconds) + + signal = np.sin(2 * np.pi * freq * np.arange(n_total) / sr) + x = np.arange(n_total) + exp_scale = np.exp(-x/5.5e3) + return max_int16 * signal * exp_scale + +engage_beep = harmonic_beep(1661.219, 0.5) +wavfile.write("engage.wav", sr, engage_beep.astype(np.int16)) +disengage_beep = harmonic_beep(1318.51, 0.5) +wavfile.write("disengage.wav", sr, disengage_beep.astype(np.int16)) diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index 463683fd3c..cd352b2ede 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -42,7 +42,7 @@ If your car has the following packages or features, then it's a good candidate f | Make | Required Package/Features | | ---- | ------------------------- | -| Acura | Any car with AcuraWatch Plus will work. AcuraWatch Plus comes standard on many newer models. | +| Acura | Any car with AcuraWatch will work. AcuraWatch comes standard on many newer models. | | Ford | Any car with Lane Centering will likely work. | | Honda | Any car with Honda Sensing will work. Honda Sensing comes standard on many newer models. | | Subaru | Any car with EyeSight will work. EyeSight comes standard on many newer models. | diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 270111524e..71d057694f 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -26,6 +26,18 @@ class MockCarState: return CS, CS_SP +BRAND_EXTRA_GEARS = { + 'ford': [GearShifter.low, GearShifter.manumatic], + 'nissan': [GearShifter.brake], + 'chrysler': [GearShifter.low], + 'honda': [GearShifter.sport], + 'toyota': [GearShifter.sport], + 'gm': [GearShifter.sport, GearShifter.low, GearShifter.eco, GearShifter.manumatic], + 'volkswagen': [GearShifter.eco, GearShifter.sport, GearShifter.manumatic], + 'hyundai': [GearShifter.sport, GearShifter.manumatic] +} + + class CarSpecificEvents: def __init__(self, CP: structs.CarParams): self.CP = CP @@ -36,17 +48,13 @@ class CarSpecificEvents: self.silent_steer_warning = True def update(self, CS: car.CarState, CS_prev: car.CarState, CC: car.CarControl): + extra_gears = BRAND_EXTRA_GEARS.get(self.CP.brand, None) + if self.CP.brand in ('body', 'mock'): events = Events() - elif self.CP.brand == 'ford': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.low, GearShifter.manumatic]) - - elif self.CP.brand == 'nissan': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.brake]) - elif self.CP.brand == 'chrysler': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.low]) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears) # Low speed steer alert hysteresis logic if self.CP.minSteerSpeed > 0. and CS.vEgo < (self.CP.minSteerSpeed + 0.5): @@ -57,7 +65,7 @@ class CarSpecificEvents: events.add(EventName.belowSteerSpeed) elif self.CP.brand == 'honda': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.sport], pcm_enable=False) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears, pcm_enable=False) if self.CP.pcmCruise and CS.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) @@ -79,7 +87,7 @@ class CarSpecificEvents: elif self.CP.brand == 'toyota': # TODO: when we check for unexpected disengagement, check gear not S1, S2, S3 - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.sport]) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears) if self.CP.openpilotLongitudinalControl: if CS.cruiseState.standstill and not CS.brakePressed: @@ -94,9 +102,7 @@ class CarSpecificEvents: events.add(EventName.manualRestart) elif self.CP.brand == 'gm': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.sport, GearShifter.low, - GearShifter.eco, GearShifter.manumatic], - pcm_enable=self.CP.pcmCruise) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears, pcm_enable=self.CP.pcmCruise) # Enabling at a standstill with brake is allowed # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs @@ -107,8 +113,7 @@ class CarSpecificEvents: events.add(EventName.resumeRequired) elif self.CP.brand == 'volkswagen': - events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], - pcm_enable=self.CP.pcmCruise) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears, pcm_enable=self.CP.pcmCruise) if self.CP.openpilotLongitudinalControl: if CS.vEgo < self.CP.minEnableSpeed + 0.5: @@ -121,15 +126,14 @@ class CarSpecificEvents: # events.add(EventName.steerTimeLimit) elif self.CP.brand == 'hyundai': - events = self.create_common_events(CS, CS_prev, extra_gears=(GearShifter.sport, GearShifter.manumatic), - pcm_enable=self.CP.pcmCruise, allow_button_cancel=False) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears, pcm_enable=self.CP.pcmCruise, allow_button_cancel=False) else: - events = self.create_common_events(CS, CS_prev) + events = self.create_common_events(CS, CS_prev, extra_gears=extra_gears) return events - def create_common_events(self, CS: structs.CarState, CS_prev: car.CarState, extra_gears=None, pcm_enable=True, + def create_common_events(self, CS: structs.CarState, CS_prev: car.CarState, extra_gears: list | None = None, pcm_enable=True, allow_button_cancel=True): events = Events() diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 47d105f993..48d174bfa0 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -22,15 +22,17 @@ from openpilot.sunnypilot.selfdrive.controls.lib.latcontrol_torque_ext import La # Additionally, there is friction in the steering wheel that needs # to be overcome to move it at all, this is compensated for too. -KP = 1.0 -KI = 0.3 -KD = 0.0 +KP = 0.8 +KI = 0.15 + INTERP_SPEEDS = [1, 1.5, 2.0, 3.0, 5, 7.5, 10, 15, 30] KP_INTERP = [250, 120, 65, 30, 11.5, 5.5, 3.5, 2.0, KP] LP_FILTER_CUTOFF_HZ = 1.2 +JERK_LOOKAHEAD_SECONDS = 0.19 +JERK_GAIN = 0.3 LAT_ACCEL_REQUEST_BUFFER_SECONDS = 1.0 -VERSION = 0 +VERSION = 1 class LatControlTorque(LatControl): def __init__(self, CP, CP_SP, CI, dt): @@ -38,13 +40,13 @@ class LatControlTorque(LatControl): self.torque_params = CP.lateralTuning.torque.as_builder() self.torque_from_lateral_accel = CI.torque_from_lateral_accel() self.lateral_accel_from_torque = CI.lateral_accel_from_torque() - self.pid = PIDController([INTERP_SPEEDS, KP_INTERP], KI, KD, rate=1/self.dt) + self.pid = PIDController([INTERP_SPEEDS, KP_INTERP], KI, rate=1/self.dt) self.update_limits() self.steering_angle_deadzone_deg = self.torque_params.steeringAngleDeadzoneDeg self.lat_accel_request_buffer_len = int(LAT_ACCEL_REQUEST_BUFFER_SECONDS / self.dt) self.lat_accel_request_buffer = deque([0.] * self.lat_accel_request_buffer_len , maxlen=self.lat_accel_request_buffer_len) - self.previous_measurement = 0.0 - self.measurement_rate_filter = FirstOrderFilter(0.0, 1 / (2 * np.pi * LP_FILTER_CUTOFF_HZ), self.dt) + self.lookahead_frames = int(JERK_LOOKAHEAD_SECONDS / self.dt) + self.jerk_filter = FirstOrderFilter(0.0, 1 / (2 * np.pi * LP_FILTER_CUTOFF_HZ), self.dt) self.extension = LatControlTorqueExt(self, CP, CP_SP, CI) @@ -76,17 +78,15 @@ class LatControlTorque(LatControl): delay_frames = int(np.clip(lat_delay / self.dt, 1, self.lat_accel_request_buffer_len)) expected_lateral_accel = self.lat_accel_request_buffer[-delay_frames] - # TODO factor out lateral jerk from error to later replace it with delay independent alternative + lookahead_idx = int(np.clip(-delay_frames + self.lookahead_frames, -self.lat_accel_request_buffer_len+1, -2)) + raw_lateral_jerk = (self.lat_accel_request_buffer[lookahead_idx+1] - self.lat_accel_request_buffer[lookahead_idx-1]) / (2 * self.dt) + desired_lateral_jerk = self.jerk_filter.update(raw_lateral_jerk) future_desired_lateral_accel = desired_curvature * CS.vEgo ** 2 self.lat_accel_request_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 + setpoint = expected_lateral_accel measurement = measured_curvature * CS.vEgo ** 2 - measurement_rate = self.measurement_rate_filter.update((measurement - self.previous_measurement) / self.dt) - self.previous_measurement = measurement - - setpoint = lat_delay * desired_lateral_jerk + expected_lateral_accel error = setpoint - measurement # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly @@ -94,15 +94,10 @@ class LatControlTorque(LatControl): ff = gravity_adjusted_future_lateral_accel # latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll ff -= self.torque_params.latAccelOffset - # 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) + ff += get_friction(error + JERK_GAIN * desired_lateral_jerk, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 - output_lataccel = self.pid.update(pid_log.error, - -measurement_rate, - feedforward=ff, - speed=CS.vEgo, - freeze_integrator=freeze_integrator) + output_lataccel = self.pid.update(pid_log.error, speed=CS.vEgo, feedforward=ff, freeze_integrator=freeze_integrator) output_torque = self.torque_from_lateral_accel(output_lataccel, self.torque_params) # Lateral acceleration torque controller extension updates diff --git a/selfdrive/locationd/helpers.py b/selfdrive/locationd/helpers.py index bf4588a40c..2a3ac8b861 100644 --- a/selfdrive/locationd/helpers.py +++ b/selfdrive/locationd/helpers.py @@ -172,7 +172,7 @@ class PoseCalibrator: ned_from_calib_euler = self._ned_from_calib(pose.orientation) angular_velocity_calib = self._transform_calib_from_device(pose.angular_velocity) acceleration_calib = self._transform_calib_from_device(pose.acceleration) - velocity_calib = self._transform_calib_from_device(pose.angular_velocity) + velocity_calib = self._transform_calib_from_device(pose.velocity) return Pose(ned_from_calib_euler, velocity_calib, acceleration_calib, angular_velocity_calib) diff --git a/selfdrive/modeld/models/driving_policy.onnx b/selfdrive/modeld/models/driving_policy.onnx index 1e764af9ba..e0eb918125 100644 --- a/selfdrive/modeld/models/driving_policy.onnx +++ b/selfdrive/modeld/models/driving_policy.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:c5a1f0655ddf266ed42ad1980389d96f47cc5e756da1fa3ca1477a920bb9b157 +oid sha256:f8fe9a71b0fd428a045a82ed50790179f77aa664391198f078e11e7b2cb2c2d7 size 13926324 diff --git a/selfdrive/modeld/models/driving_vision.onnx b/selfdrive/modeld/models/driving_vision.onnx index 441c4a16af..76c96670a9 100644 --- a/selfdrive/modeld/models/driving_vision.onnx +++ b/selfdrive/modeld/models/driving_vision.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:8f16d548ea4eb5d01518a9e90d4527cd97c31a84bcaf6f695dead8f0015fecc4 +oid sha256:1dc66bc06f250b577653ccbeaa2c6521b3d46749f601d0a1a366419e929ca438 size 46271942 diff --git a/selfdrive/modeld/tests/__init__.py b/selfdrive/modeld/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/selfdrive/modeld/tests/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py deleted file mode 100644 index 6927c9e473..0000000000 --- a/selfdrive/modeld/tests/test_modeld.py +++ /dev/null @@ -1,102 +0,0 @@ -import numpy as np -import random - -import cereal.messaging as messaging -from msgq.visionipc import VisionIpcServer, VisionStreamType -from opendbc.car.car_helpers import get_demo_car_params -from openpilot.common.params import Params -from openpilot.common.transformations.camera import DEVICE_CAMERAS -from openpilot.common.realtime import DT_MDL -from openpilot.system.manager.process_config import managed_processes -from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state - -CAM = DEVICE_CAMERAS[("tici", "ar0231")].fcam -IMG = np.zeros(int(CAM.width*CAM.height*(3/2)), dtype=np.uint8) -IMG_BYTES = IMG.flatten().tobytes() - - -class TestModeld: - - def setup_method(self): - self.vipc_server = VisionIpcServer("camerad") - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, CAM.width, CAM.height) - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, CAM.width, CAM.height) - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, CAM.width, CAM.height) - self.vipc_server.start_listener() - Params().put("CarParams", get_demo_car_params().to_bytes()) - - self.sm = messaging.SubMaster(['modelV2', 'cameraOdometry']) - self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'liveCalibration']) - - managed_processes['modeld'].start() - self.pm.wait_for_readers_to_update("roadCameraState", 10) - - def teardown_method(self): - managed_processes['modeld'].stop() - del self.vipc_server - - def _send_frames(self, frame_id, cams=None): - if cams is None: - cams = ('roadCameraState', 'wideRoadCameraState') - - cs = None - for cam in cams: - msg = messaging.new_message(cam) - cs = getattr(msg, cam) - cs.frameId = frame_id - cs.timestampSof = int((frame_id * DT_MDL) * 1e9) - cs.timestampEof = int(cs.timestampSof + (DT_MDL * 1e9)) - cam_meta = meta_from_camera_state(cam) - - self.pm.send(msg.which(), msg) - self.vipc_server.send(cam_meta.stream, IMG_BYTES, cs.frameId, - cs.timestampSof, cs.timestampEof) - return cs - - def _wait(self): - self.sm.update(5000) - if self.sm['modelV2'].frameId != self.sm['cameraOdometry'].frameId: - self.sm.update(1000) - - def test_modeld(self): - for n in range(1, 500): - cs = self._send_frames(n) - self._wait() - - mdl = self.sm['modelV2'] - assert mdl.frameId == n - assert mdl.frameIdExtra == n - assert mdl.timestampEof == cs.timestampEof - assert mdl.frameAge == 0 - assert mdl.frameDropPerc == 0 - - odo = self.sm['cameraOdometry'] - assert odo.frameId == n - assert odo.timestampEof == cs.timestampEof - - def test_dropped_frames(self): - """ - modeld should only run on consecutive road frames - """ - frame_id = -1 - road_frames = list() - for n in range(1, 50): - if (random.random() < 0.1) and n > 3: - cams = random.choice([(), ('wideRoadCameraState', )]) - self._send_frames(n, cams) - else: - self._send_frames(n) - road_frames.append(n) - self._wait() - - if len(road_frames) < 3 or road_frames[-1] - road_frames[-2] == 1: - frame_id = road_frames[-1] - - mdl = self.sm['modelV2'] - odo = self.sm['cameraOdometry'] - assert mdl.frameId == frame_id - assert mdl.frameIdExtra == frame_id - assert odo.frameId == frame_id - if n != frame_id: - assert not self.sm.updated['modelV2'] - assert not self.sm.updated['cameraOdometry'] diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 02e5aafa68..022415af6d 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -40,8 +40,8 @@ def dmonitoringd_thread(): # save rhd virtual toggle every 5 mins if (sm['driverStateV2'].frameId % 6000 == 0 and not demo_mode and - DM.wheelpos_learner.filtered_stat.n > DM.settings._WHEELPOS_FILTER_MIN_COUNT and - DM.wheel_on_right == (DM.wheelpos_learner.filtered_stat.M > DM.settings._WHEELPOS_THRESHOLD)): + DM.wheelpos.prob_offseter.filtered_stat.n > DM.settings._WHEELPOS_FILTER_MIN_COUNT and + DM.wheel_on_right == (DM.wheelpos.prob_offseter.filtered_stat.M > DM.settings._WHEELPOS_THRESHOLD)): params.put_bool_nonblocking("IsRhdDetected", DM.wheel_on_right) def main(): diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 7697e68b98..3377ce6c68 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -40,6 +40,9 @@ class DRIVER_MONITOR_SETTINGS: self._PHONE_THRESH2 = 15.0 self._PHONE_MAX_OFFSET = 0.06 self._PHONE_MIN_OFFSET = 0.025 + self._PHONE_DATA_AVG = 0.05 + self._PHONE_DATA_VAR = 3*0.005 + self._PHONE_MAX_COUNT = int(360 / self._DT_DMON) self._POSE_PITCH_THRESHOLD = 0.3133 self._POSE_PITCH_THRESHOLD_SLACK = 0.3237 @@ -47,9 +50,11 @@ class DRIVER_MONITOR_SETTINGS: self._POSE_YAW_THRESHOLD = 0.4020 self._POSE_YAW_THRESHOLD_SLACK = 0.5042 self._POSE_YAW_THRESHOLD_STRICT = self._POSE_YAW_THRESHOLD - self._PITCH_NATURAL_OFFSET = 0.029 # initial value before offset is learned + self._PITCH_NATURAL_OFFSET = 0.011 # initial value before offset is learned self._PITCH_NATURAL_THRESHOLD = 0.449 - self._YAW_NATURAL_OFFSET = 0.097 # initial value before offset is learned + self._YAW_NATURAL_OFFSET = 0.075 # initial value before offset is learned + self._PITCH_NATURAL_VAR = 3*0.01 + self._YAW_NATURAL_VAR = 3*0.05 self._PITCH_MAX_OFFSET = 0.124 self._PITCH_MIN_OFFSET = -0.0881 self._YAW_MAX_OFFSET = 0.289 @@ -70,6 +75,9 @@ class DRIVER_MONITOR_SETTINGS: self._WHEELPOS_CALIB_MIN_SPEED = 11 self._WHEELPOS_THRESHOLD = 0.5 self._WHEELPOS_FILTER_MIN_COUNT = int(15 / self._DT_DMON) # allow 15 seconds to converge wheel side + self._WHEELPOS_DATA_AVG = 0.03 + self._WHEELPOS_DATA_VAR = 3*5.5e-5 + self._WHEELPOS_MAX_COUNT = -1 self._RECOVERY_FACTOR_MAX = 5. # relative to minus step change self._RECOVERY_FACTOR_MIN = 1.25 # relative to minus step change @@ -78,30 +86,33 @@ class DRIVER_MONITOR_SETTINGS: self._MAX_TERMINAL_DURATION = int(30 / self._DT_DMON) # not allowed to engage after 30s of terminal alerts class DistractedType: + NOT_DISTRACTED = 0 DISTRACTED_POSE = 1 << 0 DISTRACTED_BLINK = 1 << 1 DISTRACTED_PHONE = 1 << 2 class DriverPose: - def __init__(self, max_trackable): + def __init__(self, settings): + pitch_filter_raw_priors = (settings._PITCH_NATURAL_OFFSET, settings._PITCH_NATURAL_VAR, 2) + yaw_filter_raw_priors = (settings._YAW_NATURAL_OFFSET, settings._YAW_NATURAL_VAR, 2) self.yaw = 0. self.pitch = 0. self.roll = 0. self.yaw_std = 0. self.pitch_std = 0. self.roll_std = 0. - self.pitch_offseter = RunningStatFilter(max_trackable=max_trackable) - self.yaw_offseter = RunningStatFilter(max_trackable=max_trackable) + self.pitch_offseter = RunningStatFilter(raw_priors=pitch_filter_raw_priors, max_trackable=settings._POSE_OFFSET_MAX_COUNT) + self.yaw_offseter = RunningStatFilter(raw_priors=yaw_filter_raw_priors, max_trackable=settings._POSE_OFFSET_MAX_COUNT) self.calibrated = False self.low_std = True self.cfactor_pitch = 1. self.cfactor_yaw = 1. -class DriverPhone: - def __init__(self, max_trackable): +class DriverProb: + def __init__(self, raw_priors, max_trackable): self.prob = 0. - self.prob_offseter = RunningStatFilter(max_trackable=max_trackable) + self.prob_offseter = RunningStatFilter(raw_priors=raw_priors, max_trackable=max_trackable) self.prob_calibrated = False class DriverBlink: @@ -140,9 +151,11 @@ class DriverMonitoring: self.settings = settings if settings is not None else DRIVER_MONITOR_SETTINGS(device_type=HARDWARE.get_device_type()) # init driver status - self.wheelpos_learner = RunningStatFilter() - self.pose = DriverPose(self.settings._POSE_OFFSET_MAX_COUNT) - self.phone = DriverPhone(self.settings._POSE_OFFSET_MAX_COUNT) + wheelpos_filter_raw_priors = (self.settings._WHEELPOS_DATA_AVG, self.settings._WHEELPOS_DATA_VAR, 2) + phone_filter_raw_priors = (self.settings._PHONE_DATA_AVG, self.settings._PHONE_DATA_VAR, 2) + self.wheelpos = DriverProb(raw_priors=wheelpos_filter_raw_priors, max_trackable=self.settings._WHEELPOS_MAX_COUNT) + self.phone = DriverProb(raw_priors=phone_filter_raw_priors, max_trackable=self.settings._PHONE_MAX_COUNT) + self.pose = DriverPose(settings=self.settings) self.blink = DriverBlink() self.always_on = always_on @@ -234,8 +247,11 @@ class DriverMonitoring: self.settings._YAW_MIN_OFFSET), self.settings._YAW_MAX_OFFSET) pitch_error = 0 if pitch_error > 0 else abs(pitch_error) # no positive pitch limit yaw_error = abs(yaw_error) - if pitch_error > (self.settings._POSE_PITCH_THRESHOLD*self.pose.cfactor_pitch if self.pose.calibrated else self.settings._PITCH_NATURAL_THRESHOLD) or \ - yaw_error > self.settings._POSE_YAW_THRESHOLD*self.pose.cfactor_yaw: + + pitch_threshold = self.settings._POSE_PITCH_THRESHOLD * self.pose.cfactor_pitch if self.pose.calibrated else self.settings._PITCH_NATURAL_THRESHOLD + yaw_threshold = self.settings._POSE_YAW_THRESHOLD * self.pose.cfactor_yaw + + if pitch_error > pitch_threshold or yaw_error > yaw_threshold: distracted_types.append(DistractedType.DISTRACTED_POSE) if (self.blink.left + self.blink.right)*0.5 > self.settings._BLINK_THRESHOLD: @@ -256,9 +272,12 @@ class DriverMonitoring: # calibrates only when there's movement and either face detected if car_speed > self.settings._WHEELPOS_CALIB_MIN_SPEED and (driver_state.leftDriverData.faceProb > self.settings._FACE_THRESHOLD or driver_state.rightDriverData.faceProb > self.settings._FACE_THRESHOLD): - self.wheelpos_learner.push_and_update(rhd_pred) - if self.wheelpos_learner.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT or demo_mode: - self.wheel_on_right = self.wheelpos_learner.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD + self.wheelpos.prob_offseter.push_and_update(rhd_pred) + + self.wheelpos.prob_calibrated = self.wheelpos.prob_offseter.filtered_stat.n > self.settings._WHEELPOS_FILTER_MIN_COUNT + + if self.wheelpos.prob_calibrated or demo_mode: + self.wheel_on_right = self.wheelpos.prob_offseter.filtered_stat.M > self.settings._WHEELPOS_THRESHOLD else: self.wheel_on_right = self.wheel_on_right_default # use default/saved if calibration is unfinished # make sure no switching when engaged diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index cdd4301fcf..4a58e321fc 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b508f43fb0481bce0859c9b6ab4f45ee690b8dab \ No newline at end of file +e0ad86508edb61b3eaa1b84662c515d2c3368295 \ No newline at end of file diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 27cc17624e..b9506d0806 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -206,8 +206,9 @@ class TestOnroad: result += "-------------- UI Draw Timing ------------------\n" result += "------------------------------------------------\n" - # skip first few frames -- connecting to vipc - ts = self.ts['uiDebug']['drawTimeMillis'][15:] + # other processes preempt ui while starting up + offset = int(20 * LOG_OFFSET) + ts = self.ts['uiDebug']['drawTimeMillis'][offset:] result += f"min {min(ts):.2f}ms\n" result += f"max {max(ts):.2f}ms\n" result += f"std {np.std(ts):.2f}ms\n" diff --git a/selfdrive/ui/layouts/settings/firehose.py b/selfdrive/ui/layouts/settings/firehose.py index 5ab82fd8f5..18514feeb9 100644 --- a/selfdrive/ui/layouts/settings/firehose.py +++ b/selfdrive/ui/layouts/settings/firehose.py @@ -1,19 +1,11 @@ import pyray as rl -import time -import threading -from openpilot.common.api import api_get -from openpilot.common.params import Params -from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.ui.ui_state import ui_state -from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE from openpilot.system.ui.lib.multilang import tr, trn, tr_noop 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.wrap_text import wrap_text -from openpilot.system.ui.widgets import Widget -from openpilot.selfdrive.ui.lib.api_helpers import get_token +from openpilot.selfdrive.ui.mici.layouts.settings.firehose import FirehoseLayoutBase TITLE = tr_noop("Firehose Mode") DESCRIPTION = tr_noop( @@ -32,50 +24,17 @@ INSTRUCTIONS = tr_noop( ) -class FirehoseLayout(Widget): - PARAM_KEY = "ApiCache_FirehoseStats" - GREEN = rl.Color(46, 204, 113, 255) - RED = rl.Color(231, 76, 60, 255) - GRAY = rl.Color(68, 68, 68, 255) - LIGHT_GRAY = rl.Color(228, 228, 228, 255) - UPDATE_INTERVAL = 30 # seconds - +class FirehoseLayout(FirehoseLayoutBase): def __init__(self): super().__init__() - self.params = Params() - self.segment_count = self._get_segment_count() - self.scroll_panel = GuiScrollPanel() - self._content_height = 0 - - self.running = True - self.update_thread = threading.Thread(target=self._update_loop, daemon=True) - self.update_thread.start() - self.last_update_time = 0 - - def show_event(self): - self.scroll_panel.set_offset(0) - - def _get_segment_count(self) -> int: - stats = self.params.get(self.PARAM_KEY) - if not stats: - return 0 - try: - return int(stats.get("firehose", 0)) - except Exception: - cloudlog.exception(f"Failed to decode firehose stats: {stats}") - return 0 - - def __del__(self): - self.running = False - if self.update_thread and self.update_thread.is_alive(): - self.update_thread.join(timeout=1.0) + self._scroll_panel = GuiScrollPanel() def _render(self, rect: rl.Rectangle): # Calculate content dimensions content_rect = rl.Rectangle(rect.x, rect.y, rect.width, self._content_height) # Handle scrolling and render with clipping - scroll_offset = self.scroll_panel.update(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)) self._content_height = self._render_content(rect, scroll_offset) rl.end_scissor_mode() @@ -107,9 +66,9 @@ class FirehoseLayout(Widget): y += 20 + 20 # Contribution count (if available) - if self.segment_count > 0: + if self._segment_count > 0: 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) + "{} 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 += 20 + 20 @@ -121,7 +80,7 @@ class FirehoseLayout(Widget): y = self._draw_wrapped_text(x, y, w, tr(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)) + return int(round(y - self._scroll_panel.offset + 40)) def _draw_wrapped_text(self, x, y, width, text, font, font_size, color): wrapped = wrap_text(font, text, font_size, width) @@ -129,32 +88,3 @@ class FirehoseLayout(Widget): rl.draw_text_ex(font, line, rl.Vector2(x, y), font_size, 0, color) y += font_size * FONT_SCALE return round(y) - - def _get_status(self) -> tuple[str, rl.Color]: - network_type = ui_state.sm["deviceState"].networkType - network_metered = ui_state.sm["deviceState"].networkMetered - - if not network_metered and network_type != 0: # Not metered and connected - return tr("ACTIVE"), self.GREEN - else: - return tr("INACTIVE: connect to an unmetered network"), self.RED - - def _fetch_firehose_stats(self): - try: - dongle_id = self.params.get("DongleId") - if not dongle_id or dongle_id == UNREGISTERED_DONGLE_ID: - return - identity_token = get_token(dongle_id) - response = api_get(f"v1/devices/{dongle_id}/firehose_stats", access_token=identity_token) - if response.status_code == 200: - data = response.json() - self.segment_count = data.get("firehose", 0) - self.params.put(self.PARAM_KEY, data) - except Exception as e: - cloudlog.error(f"Failed to fetch firehose stats: {e}") - - def _update_loop(self): - while self.running: - if not ui_state.started: - self._fetch_firehose_stats() - time.sleep(self.UPDATE_INTERVAL) diff --git a/selfdrive/ui/layouts/settings/software.py b/selfdrive/ui/layouts/settings/software.py index c4f899d798..e4c3098c2e 100644 --- a/selfdrive/ui/layouts/settings/software.py +++ b/selfdrive/ui/layouts/settings/software.py @@ -17,6 +17,13 @@ if gui_app.sunnypilot_ui(): # TODO: remove this. updater fails to respond on startup if time is not correct UPDATED_TIMEOUT = 10 # seconds to wait for updated to respond +# Mapping updater internal states to translated display strings +STATE_TO_DISPLAY_TEXT = { + "checking...": tr("checking..."), + "downloading...": tr("downloading..."), + "finalizing update...": tr("finalizing update..."), +} + def time_ago(date: datetime.datetime | None) -> str: if not date: @@ -103,7 +110,9 @@ class SoftwareLayout(Widget): # Updater responded self._waiting_for_updater = False self._download_btn.action_item.set_enabled(False) - self._download_btn.action_item.set_value(updater_state) + # Use the mapping, with a fallback to the original state string + display_text = STATE_TO_DISPLAY_TEXT.get(updater_state, updater_state) + self._download_btn.action_item.set_value(display_text) else: if failed_count > 0: self._download_btn.action_item.set_value(tr("failed to check for update")) diff --git a/selfdrive/ui/lib/prime_state.py b/selfdrive/ui/lib/prime_state.py index fc72b4f9c6..e1ef387bf7 100644 --- a/selfdrive/ui/lib/prime_state.py +++ b/selfdrive/ui/lib/prime_state.py @@ -67,8 +67,10 @@ class PrimeState: cloudlog.info(f"Prime type updated to {prime_type}") def _worker_thread(self) -> None: + from openpilot.selfdrive.ui.ui_state import ui_state, device while self._running: - self._fetch_prime_status() + if not ui_state.started and device._awake: + self._fetch_prime_status() for _ in range(int(self.FETCH_INTERVAL / self.SLEEP_INTERVAL)): if not self._running: diff --git a/selfdrive/ui/mici/layouts/home.py b/selfdrive/ui/mici/layouts/home.py index fd4de9a717..750a30b73a 100644 --- a/selfdrive/ui/mici/layouts/home.py +++ b/selfdrive/ui/mici/layouts/home.py @@ -3,18 +3,16 @@ import time from cereal import log import pyray as rl from collections.abc import Callable -from openpilot.system.ui.widgets.label import gui_label, MiciLabel +from openpilot.system.ui.widgets.label import gui_label, MiciLabel, UnifiedLabel from openpilot.system.ui.widgets import Widget from openpilot.system.ui.lib.application import gui_app, FontWeight, DEFAULT_TEXT_COLOR, MousePos from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.system.ui.text import wrap_text -from openpilot.system.version import training_version +from openpilot.system.version import training_version, RELEASE_BRANCHES HEAD_BUTTON_FONT_SIZE = 40 HOME_PADDING = 8 -RELEASE_BRANCH = "release3" - NetworkType = log.DeviceState.NetworkType NETWORK_TYPES = { @@ -115,7 +113,7 @@ class MiciHomeLayout(Widget): self._version_label = MiciLabel("", font_size=36, font_weight=FontWeight.ROMAN) self._large_version_label = MiciLabel("", font_size=64, color=rl.GRAY, font_weight=FontWeight.ROMAN) self._date_label = MiciLabel("", font_size=36, color=rl.GRAY, font_weight=FontWeight.ROMAN) - self._branch_label = MiciLabel("", font_size=36, color=rl.GRAY, font_weight=FontWeight.ROMAN, elide_right=False, scroll=True) + self._branch_label = UnifiedLabel("", font_size=36, text_color=rl.GRAY, font_weight=FontWeight.ROMAN, scroll=True) self._version_commit_label = MiciLabel("", font_size=36, color=rl.GRAY, font_weight=FontWeight.ROMAN) def show_event(self): @@ -187,27 +185,22 @@ class MiciHomeLayout(Widget): if self._version_text is not None: # release branch - if self._version_text[0] == RELEASE_BRANCH: - version_pos = rl.Vector2(text_pos.x, text_pos.y + self._openpilot_label.font_size + 16) - self._large_version_label.set_text(self._version_text[0]) - self._large_version_label.set_position(version_pos.x, version_pos.y) - self._large_version_label.render() + release_branch = self._version_text[1] in RELEASE_BRANCHES + version_pos = rl.Rectangle(text_pos.x, text_pos.y + self._openpilot_label.font_size + 16, 100, 44) + self._version_label.set_text(self._version_text[0]) + self._version_label.set_position(version_pos.x, version_pos.y) + self._version_label.render() - else: - version_pos = rl.Rectangle(text_pos.x, text_pos.y + self._openpilot_label.font_size + 16, 100, 44) - self._version_label.set_text(self._version_text[0]) - self._version_label.set_position(version_pos.x, version_pos.y) - self._version_label.render() + self._date_label.set_text(" " + self._version_text[3]) + self._date_label.set_position(version_pos.x + self._version_label.rect.width + 10, version_pos.y) + self._date_label.render() - self._date_label.set_text(" " + self._version_text[3]) - self._date_label.set_position(version_pos.x + self._version_label.rect.width + 10, version_pos.y) - self._date_label.render() - - self._branch_label.set_width(gui_app.width - self._version_label.rect.width - self._date_label.rect.width - 32) - self._branch_label.set_text(" " + self._version_text[1]) - self._branch_label.set_position(version_pos.x + self._version_label.rect.width + self._date_label.rect.width + 20, version_pos.y) - self._branch_label.render() + self._branch_label.set_max_width(gui_app.width - self._version_label.rect.width - self._date_label.rect.width - 32) + self._branch_label.set_text(" " + ("release" if release_branch else self._version_text[1])) + self._branch_label.set_position(version_pos.x + self._version_label.rect.width + self._date_label.rect.width + 20, version_pos.y) + self._branch_label.render() + if not release_branch: # 2nd line self._version_commit_label.set_text(self._version_text[2]) self._version_commit_label.set_position(version_pos.x, version_pos.y + self._date_label.font_size + 7) diff --git a/selfdrive/ui/mici/layouts/offroad_alerts.py b/selfdrive/ui/mici/layouts/offroad_alerts.py index cdde40d4a6..b01dae6aeb 100644 --- a/selfdrive/ui/mici/layouts/offroad_alerts.py +++ b/selfdrive/ui/mici/layouts/offroad_alerts.py @@ -5,6 +5,7 @@ from dataclasses import dataclass from enum import IntEnum from openpilot.common.params import Params from openpilot.selfdrive.selfdrived.alertmanager import OFFROAD_ALERTS +from openpilot.system.hardware import HARDWARE from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets.label import UnifiedLabel from openpilot.system.ui.widgets.scroller import Scroller @@ -220,6 +221,7 @@ class MiciOffroadAlerts(Widget): update_alert_data = AlertData(key="UpdateAvailable", text="", severity=-1) self.sorted_alerts.append(update_alert_data) update_alert_item = AlertItem(update_alert_data) + update_alert_item.set_click_callback(lambda: HARDWARE.reboot()) self.alert_items.append(update_alert_item) self._scroller.add_widget(update_alert_item) @@ -244,18 +246,18 @@ class MiciOffroadAlerts(Widget): if update_alert_data: if update_available: - # Default text - update_alert_data.text = "update available. go to comma.ai/blog to read the release notes." + version_string = "" # Get new version description and parse version and date new_desc = self.params.get("UpdaterNewDescription") or "" if new_desc: - # Parse description (format: "version / branch / commit / date") + # format: "version / branch / commit / date" parts = new_desc.split(" / ") if len(parts) > 3: version, date = parts[0], parts[3] - update_alert_data.text = f"update available\n sunnypilot {version}, {date}. go to comma.ai/blog to read the release notes." + version_string = f"\nsunnypilot {version}, {date}\n" + update_alert_data.text = f"Update available {version_string}. Click to update. Read the release notes at blog.comma.ai." update_alert_data.visible = True active_count += 1 else: diff --git a/selfdrive/ui/mici/layouts/onboarding.py b/selfdrive/ui/mici/layouts/onboarding.py index 5f20cf7c78..38dd70cea2 100644 --- a/selfdrive/ui/mici/layouts/onboarding.py +++ b/selfdrive/ui/mici/layouts/onboarding.py @@ -1,6 +1,7 @@ from enum import IntEnum from collections.abc import Callable +import weakref import pyray as rl from openpilot.system.ui.lib.application import FontWeight, gui_app from openpilot.system.ui.widgets import Widget @@ -92,11 +93,10 @@ class TrainingGuideDMTutorial(Widget): super().__init__() self._title_header = TermsHeader("fill the circle to continue", gui_app.texture("icons_mici/setup/green_dm.png", 60, 60)) - self._original_continue_callback = continue_callback - # Wrap the continue callback to restore settings def wrapped_continue_callback(): - self._restore_settings() + device.set_offroad_brightness(None) + device.reset_interactive_timeout() continue_callback() self._dialog = DriverCameraSetupDialog(wrapped_continue_callback) @@ -114,10 +114,6 @@ class TrainingGuideDMTutorial(Widget): device.set_offroad_brightness(100) device.reset_interactive_timeout(300) # 5 minutes - def _restore_settings(self): - device.set_offroad_brightness(None) - device.reset_interactive_timeout() - def _update_state(self): super()._update_state() if device.awake: @@ -150,7 +146,7 @@ class TrainingGuideRecordFront(SetupTermsPage): super().__init__(on_continue, back_callback=on_back, back_text="no", continue_text="yes") self._title_header = TermsHeader("improve driver monitoring", gui_app.texture("icons_mici/setup/green_dm.png", 60, 60)) - self._dm_label = UnifiedLabel("Do you want to upload driver camera data to improve driver monitoring?", 42, + self._dm_label = UnifiedLabel("Do you want to upload driver camera data?", 42, FontWeight.ROMAN) def show_event(self): @@ -214,11 +210,17 @@ class TrainingGuide(Widget): self._completed_callback = completed_callback self._step = 0 + self_ref = weakref.ref(self) + + def on_continue(): + if obj := self_ref(): + obj._advance_step() + self._steps = [ - TrainingGuideAttentionNotice(continue_callback=self._advance_step), - TrainingGuidePreDMTutorial(continue_callback=self._advance_step), - TrainingGuideDMTutorial(continue_callback=self._advance_step), - TrainingGuideRecordFront(continue_callback=self._advance_step), + TrainingGuideAttentionNotice(continue_callback=on_continue), + TrainingGuidePreDMTutorial(continue_callback=on_continue), + TrainingGuideDMTutorial(continue_callback=on_continue), + TrainingGuideRecordFront(continue_callback=on_continue), ] def _advance_step(self): diff --git a/selfdrive/ui/mici/layouts/settings/device.py b/selfdrive/ui/mici/layouts/settings/device.py index 1d5e4989ec..81f0e870ef 100644 --- a/selfdrive/ui/mici/layouts/settings/device.py +++ b/selfdrive/ui/mici/layouts/settings/device.py @@ -39,7 +39,7 @@ class MiciFccModal(NavWidget): content_height += self._fcc_logo.height + 20 scroll_content_rect = rl.Rectangle(rect.x, rect.y, rect.width, content_height) - scroll_offset = self._scroll_panel.update(rect, scroll_content_rect.height) + scroll_offset = round(self._scroll_panel.update(rect, scroll_content_rect.height)) fcc_pos = rl.Vector2(rect.x + 20, rect.y + 20 + scroll_offset) diff --git a/selfdrive/ui/mici/layouts/settings/firehose.py b/selfdrive/ui/mici/layouts/settings/firehose.py index 18731d675e..462b1fc813 100644 --- a/selfdrive/ui/mici/layouts/settings/firehose.py +++ b/selfdrive/ui/mici/layouts/settings/firehose.py @@ -6,14 +6,13 @@ from openpilot.common.api import api_get from openpilot.common.params import Params from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.ui.lib.api_helpers import get_token -from openpilot.selfdrive.ui.ui_state import ui_state +from openpilot.selfdrive.ui.ui_state import ui_state, device from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.scroll_panel2 import GuiScrollPanel2 from openpilot.system.ui.lib.multilang import tr, trn, tr_noop -from openpilot.system.ui.widgets import NavWidget - +from openpilot.system.ui.widgets import Widget, NavWidget TITLE = tr_noop("Firehose Mode") DESCRIPTION = tr_noop( @@ -34,9 +33,7 @@ FAQ_ITEMS = [ ] -class FirehoseLayoutMici(NavWidget): - BACK_TOUCH_AREA_PERCENTAGE = 0.1 - +class FirehoseLayoutBase(Widget): PARAM_KEY = "ApiCache_FirehoseStats" GREEN = rl.Color(46, 204, 113, 255) RED = rl.Color(231, 76, 60, 255) @@ -44,12 +41,10 @@ class FirehoseLayoutMici(NavWidget): LIGHT_GRAY = rl.Color(228, 228, 228, 255) UPDATE_INTERVAL = 30 # seconds - def __init__(self, back_callback): + def __init__(self): super().__init__() - self.set_back_callback(back_callback) - - self.params = Params() - self.segment_count = self._get_segment_count() + self._params = Params() + self._segment_count = self._get_segment_count() self._scroll_panel = GuiScrollPanel2(horizontal=False) self._content_height = 0 @@ -71,7 +66,7 @@ class FirehoseLayoutMici(NavWidget): self._scroll_panel.set_offset(0) def _get_segment_count(self) -> int: - stats = self.params.get(self.PARAM_KEY) + stats = self._params.get(self.PARAM_KEY) if not stats: return 0 try: @@ -83,7 +78,7 @@ class FirehoseLayoutMici(NavWidget): def _render(self, rect: rl.Rectangle): # compute total content height for scrolling content_height = self._measure_content_height(rect) - scroll_offset = self._scroll_panel.update(rect, content_height) + scroll_offset = round(self._scroll_panel.update(rect, content_height)) # start drawing with offset x = int(rect.x + 40) @@ -111,9 +106,9 @@ class FirehoseLayoutMici(NavWidget): y += 20 # Contribution count (if available) - if self.segment_count > 0: + if self._segment_count > 0: 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) + "{} 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), 42, rl.WHITE) y += 20 @@ -165,9 +160,9 @@ class FirehoseLayoutMici(NavWidget): y += int(len(status_lines) * 48 * FONT_SCALE) + 20 # Contribution count - if self.segment_count > 0: + if self._segment_count > 0: 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) + "{} segments of your driving is in the training dataset so far.", self._segment_count).format(self._segment_count) contrib_lines = wrap_text(gui_app.font(FontWeight.BOLD), contrib_text, 42, w) y += int(len(contrib_lines) * 42 * FONT_SCALE) + 20 @@ -204,20 +199,28 @@ class FirehoseLayoutMici(NavWidget): def _fetch_firehose_stats(self): try: - dongle_id = self.params.get("DongleId") + dongle_id = self._params.get("DongleId") if not dongle_id or dongle_id == UNREGISTERED_DONGLE_ID: return identity_token = get_token(dongle_id) response = api_get(f"v1/devices/{dongle_id}/firehose_stats", access_token=identity_token) if response.status_code == 200: data = response.json() - self.segment_count = data.get("firehose", 0) - self.params.put(self.PARAM_KEY, data) + self._segment_count = data.get("firehose", 0) + self._params.put(self.PARAM_KEY, data) except Exception as e: cloudlog.error(f"Failed to fetch firehose stats: {e}") def _update_loop(self): while self._running: - if not ui_state.started: + if not ui_state.started and device._awake: self._fetch_firehose_stats() time.sleep(self.UPDATE_INTERVAL) + + +class FirehoseLayout(FirehoseLayoutBase, NavWidget): + BACK_TOUCH_AREA_PERCENTAGE = 0.1 + + def __init__(self, back_callback): + super().__init__() + self.set_back_callback(back_callback) diff --git a/selfdrive/ui/mici/layouts/settings/network/__init__.py b/selfdrive/ui/mici/layouts/settings/network/__init__.py new file mode 100644 index 0000000000..d085fdf55f --- /dev/null +++ b/selfdrive/ui/mici/layouts/settings/network/__init__.py @@ -0,0 +1,182 @@ +import pyray as rl +from enum import IntEnum +from collections.abc import Callable + +from openpilot.system.ui.widgets.scroller import Scroller +from openpilot.selfdrive.ui.mici.layouts.settings.network.wifi_ui import WifiUIMici +from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigMultiToggle, BigToggle, BigParamControl +from openpilot.selfdrive.ui.mici.widgets.dialog import BigInputDialog +from openpilot.selfdrive.ui.ui_state import ui_state +from openpilot.selfdrive.ui.lib.prime_state import PrimeType +from openpilot.system.ui.lib.application import gui_app +from openpilot.system.ui.widgets import NavWidget +from openpilot.system.ui.lib.wifi_manager import WifiManager, Network, MeteredType + + +class NetworkPanelType(IntEnum): + NONE = 0 + WIFI = 1 + + +class NetworkLayoutMici(NavWidget): + def __init__(self, back_callback: Callable): + super().__init__() + + self._current_panel = NetworkPanelType.WIFI + self.set_back_enabled(lambda: self._current_panel == NetworkPanelType.NONE) + + self._wifi_manager = WifiManager() + self._wifi_manager.set_active(False) + self._wifi_ui = WifiUIMici(self._wifi_manager, back_callback=lambda: self._switch_to_panel(NetworkPanelType.NONE)) + + self._wifi_manager.add_callbacks( + networks_updated=self._on_network_updated, + ) + + _tethering_icon = "icons_mici/settings/network/tethering.png" + + # ******** Tethering ******** + def tethering_toggle_callback(checked: bool): + self._tethering_toggle_btn.set_enabled(False) + self._network_metered_btn.set_enabled(False) + self._wifi_manager.set_tethering_active(checked) + + self._tethering_toggle_btn = BigToggle("enable tethering", "", toggle_callback=tethering_toggle_callback) + + def tethering_password_callback(password: str): + if password: + self._wifi_manager.set_tethering_password(password) + + def tethering_password_clicked(): + tethering_password = self._wifi_manager.tethering_password + dlg = BigInputDialog("enter password...", tethering_password, minimum_length=8, + confirm_callback=tethering_password_callback) + gui_app.set_modal_overlay(dlg) + + txt_tethering = gui_app.texture(_tethering_icon, 64, 53) + self._tethering_password_btn = BigButton("tethering password", "", txt_tethering) + self._tethering_password_btn.set_click_callback(tethering_password_clicked) + + # ******** IP Address ******** + self._ip_address_btn = BigButton("IP Address", "Not connected") + + # ******** Network Metered ******** + def network_metered_callback(value: str): + self._network_metered_btn.set_enabled(False) + metered = { + 'default': MeteredType.UNKNOWN, + 'metered': MeteredType.YES, + 'unmetered': MeteredType.NO + }.get(value, MeteredType.UNKNOWN) + self._wifi_manager.set_current_network_metered(metered) + + # TODO: signal for current network metered type when changing networks, this is wrong until you press it once + # TODO: disable when not connected + self._network_metered_btn = BigMultiToggle("network usage", ["default", "metered", "unmetered"], select_callback=network_metered_callback) + self._network_metered_btn.set_enabled(False) + + wifi_button = BigButton("wi-fi") + wifi_button.set_click_callback(lambda: self._switch_to_panel(NetworkPanelType.WIFI)) + + # ******** Advanced settings ******** + # ******** Roaming toggle ******** + self._roaming_btn = BigParamControl("enable roaming", "GsmRoaming", toggle_callback=self._toggle_roaming) + + # ******** APN settings ******** + self._apn_btn = BigButton("apn settings", "edit") + self._apn_btn.set_click_callback(self._edit_apn) + + # ******** Cellular metered toggle ******** + self._cellular_metered_btn = BigParamControl("cellular metered", "GsmMetered", toggle_callback=self._toggle_cellular_metered) + + # Main scroller ---------------------------------- + self._scroller = Scroller([ + wifi_button, + self._network_metered_btn, + self._tethering_toggle_btn, + self._tethering_password_btn, + # /* Advanced settings + self._roaming_btn, + self._apn_btn, + self._cellular_metered_btn, + # */ + self._ip_address_btn, + ], snap_items=False) + + # Set initial config + roaming_enabled = ui_state.params.get_bool("GsmRoaming") + metered = ui_state.params.get_bool("GsmMetered") + self._wifi_manager.update_gsm_settings(roaming_enabled, ui_state.params.get("GsmApn") or "", metered) + + # Set up back navigation + self.set_back_callback(back_callback) + + def _update_state(self): + super()._update_state() + + # If not using prime SIM, show GSM settings and enable IPv4 forwarding + show_cell_settings = ui_state.prime_state.get_type() in (PrimeType.NONE, PrimeType.LITE) + self._wifi_manager.set_ipv4_forward(show_cell_settings) + self._roaming_btn.set_visible(show_cell_settings) + self._apn_btn.set_visible(show_cell_settings) + self._cellular_metered_btn.set_visible(show_cell_settings) + + def show_event(self): + super().show_event() + self._current_panel = NetworkPanelType.NONE + self._wifi_ui.show_event() + self._scroller.show_event() + + def hide_event(self): + super().hide_event() + self._wifi_ui.hide_event() + + def _toggle_roaming(self, checked: bool): + self._wifi_manager.update_gsm_settings(checked, ui_state.params.get("GsmApn") or "", ui_state.params.get_bool("GsmMetered")) + + def _edit_apn(self): + def update_apn(apn: str): + apn = apn.strip() + if apn == "": + ui_state.params.remove("GsmApn") + else: + ui_state.params.put("GsmApn", apn) + + self._wifi_manager.update_gsm_settings(ui_state.params.get_bool("GsmRoaming"), apn, ui_state.params.get_bool("GsmMetered")) + + current_apn = ui_state.params.get("GsmApn") or "" + dlg = BigInputDialog("enter APN", current_apn, minimum_length=0, confirm_callback=update_apn) + gui_app.set_modal_overlay(dlg) + + def _toggle_cellular_metered(self, checked: bool): + self._wifi_manager.update_gsm_settings(ui_state.params.get_bool("GsmRoaming"), ui_state.params.get("GsmApn") or "", checked) + + def _on_network_updated(self, networks: list[Network]): + # Update tethering state + tethering_active = self._wifi_manager.is_tethering_active() + # TODO: use real signals (like activated/settings changed, etc.) to speed up re-enabling buttons + self._tethering_toggle_btn.set_enabled(True) + self._network_metered_btn.set_enabled(lambda: not tethering_active and bool(self._wifi_manager.ipv4_address)) + self._tethering_toggle_btn.set_checked(tethering_active) + + # Update IP address + self._ip_address_btn.set_value(self._wifi_manager.ipv4_address or "Not connected") + + # Update network metered + self._network_metered_btn.set_value( + { + MeteredType.UNKNOWN: 'default', + MeteredType.YES: 'metered', + MeteredType.NO: 'unmetered' + }.get(self._wifi_manager.current_network_metered, 'default')) + + def _switch_to_panel(self, panel_type: NetworkPanelType): + self._current_panel = panel_type + + def _render(self, rect: rl.Rectangle): + self._wifi_manager.process_callbacks() + + if self._current_panel == NetworkPanelType.WIFI: + self._wifi_ui.render(rect) + else: + self._scroller.render(rect) diff --git a/selfdrive/ui/mici/layouts/settings/network.py b/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py similarity index 77% rename from selfdrive/ui/mici/layouts/settings/network.py rename to selfdrive/ui/mici/layouts/settings/network/wifi_ui.py index a62c1d153a..18c4dd5d6d 100644 --- a/selfdrive/ui/mici/layouts/settings/network.py +++ b/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py @@ -1,28 +1,20 @@ import math import numpy as np import pyray as rl -from enum import IntEnum from collections.abc import Callable from openpilot.common.swaglog import cloudlog -from openpilot.system.ui.widgets.scroller import Scroller from openpilot.system.ui.widgets.label import UnifiedLabel -from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigMultiToggle, BigToggle from openpilot.selfdrive.ui.mici.widgets.dialog import BigMultiOptionDialog, BigInputDialog, BigDialogOptionButton, BigConfirmationDialogV2 from openpilot.system.ui.lib.application import gui_app, MousePos, FontWeight from openpilot.system.ui.widgets import Widget, NavWidget -from openpilot.system.ui.lib.wifi_manager import WifiManager, Network, SecurityType, MeteredType +from openpilot.system.ui.lib.wifi_manager import WifiManager, Network, SecurityType def normalize_ssid(ssid: str) -> str: return ssid.replace("’", "'") # for iPhone hotspots -class NetworkPanelType(IntEnum): - NONE = 0 - WIFI = 1 - - class LoadingAnimation(Widget): def _render(self, _): cx = int(self._rect.x + 70) @@ -91,11 +83,13 @@ class WifiIcon(Widget): class WifiItem(BigDialogOptionButton): LEFT_MARGIN = 20 + HEIGHT = 54 + SELECTED_HEIGHT = 74 def __init__(self, network: Network): super().__init__(network.ssid) - self.set_rect(rl.Rectangle(0, 0, gui_app.width, 64)) + self.set_rect(rl.Rectangle(0, 0, gui_app.width, self.HEIGHT)) self._selected_txt = gui_app.texture("icons_mici/settings/network/new/wifi_selected.png", 48, 96) @@ -103,6 +97,10 @@ class WifiItem(BigDialogOptionButton): self._wifi_icon = WifiIcon() self._wifi_icon.set_current_network(network) + def set_selected(self, selected: bool): + super().set_selected(selected) + self._rect.height = self.SELECTED_HEIGHT if selected else self.HEIGHT + def set_current_network(self, network: Network): self._network = network self._wifi_icon.set_current_network(network) @@ -117,7 +115,7 @@ class WifiItem(BigDialogOptionButton): self._wifi_icon.render(rl.Rectangle( self._rect.x + self.LEFT_MARGIN, self._rect.y, - self._rect.height, + self.SELECTED_HEIGHT, self._rect.height )) @@ -126,7 +124,7 @@ class WifiItem(BigDialogOptionButton): self._label.set_color(rl.Color(255, 255, 255, int(255 * 0.9))) self._label.set_font_weight(FontWeight.DISPLAY) else: - self._label.set_font_size(70) + self._label.set_font_size(54) self._label.set_color(rl.Color(255, 255, 255, int(255 * 0.58))) self._label.set_font_weight(FontWeight.DISPLAY_REGULAR) @@ -215,7 +213,7 @@ class NetworkInfoPage(NavWidget): self._connect_btn.set_click_callback(lambda: connect_callback(self._network.ssid) if self._network is not None else None) self._title = UnifiedLabel("", 64, FontWeight.DISPLAY, rl.Color(255, 255, 255, int(255 * 0.9)), - alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE) + alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE, scroll=True) self._subtitle = UnifiedLabel("", 36, FontWeight.ROMAN, rl.Color(255, 255, 255, int(255 * 0.9 * 0.65)), alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE) @@ -225,6 +223,10 @@ class NetworkInfoPage(NavWidget): self._network: Network | None = None self._connecting: Callable[[], str | None] | None = None + def show_event(self): + super().show_event() + self._title.reset_scroll() + def update_networks(self, networks: dict[str, Network]): # update current network from latest scan results for ssid, network in networks.items(): @@ -392,7 +394,7 @@ class WifiUIMici(BigMultiOptionDialog): self._network_info_page.set_current_network(_network) self._should_open_network_info_page = True - network_button.set_click_callback(lambda _net=network,_button=network_button: _button._selected and show_network_info_page(_net)) + network_button.set_click_callback(lambda _net=network, _button=network_button: _button._selected and show_network_info_page(_net)) self.add_button(network_button) @@ -443,116 +445,3 @@ class WifiUIMici(BigMultiOptionDialog): if not self._networks: self._loading_animation.render(self._rect) - - -class NetworkLayoutMici(NavWidget): - def __init__(self, back_callback: Callable): - super().__init__() - - self._current_panel = NetworkPanelType.WIFI - self.set_back_enabled(lambda: self._current_panel == NetworkPanelType.NONE) - - self._wifi_manager = WifiManager() - self._wifi_manager.set_active(False) - self._wifi_ui = WifiUIMici(self._wifi_manager, back_callback=lambda: self._switch_to_panel(NetworkPanelType.NONE)) - - self._wifi_manager.add_callbacks( - networks_updated=self._on_network_updated, - ) - - _tethering_icon = "icons_mici/settings/network/tethering.png" - - # ******** Tethering ******** - def tethering_toggle_callback(checked: bool): - self._tethering_toggle_btn.set_enabled(False) - self._network_metered_btn.set_enabled(False) - self._wifi_manager.set_tethering_active(checked) - - self._tethering_toggle_btn = BigToggle("enable tethering", "", toggle_callback=tethering_toggle_callback) - - def tethering_password_callback(password: str): - if password: - self._wifi_manager.set_tethering_password(password) - - def tethering_password_clicked(): - tethering_password = self._wifi_manager.tethering_password - dlg = BigInputDialog("enter password...", tethering_password, minimum_length=8, - confirm_callback=tethering_password_callback) - gui_app.set_modal_overlay(dlg) - - txt_tethering = gui_app.texture(_tethering_icon, 64, 53) - self._tethering_password_btn = BigButton("tethering password", "", txt_tethering) - self._tethering_password_btn.set_click_callback(tethering_password_clicked) - - # ******** IP Address ******** - self._ip_address_btn = BigButton("IP Address", "Not connected") - - # ******** Network Metered ******** - def network_metered_callback(value: str): - self._network_metered_btn.set_enabled(False) - metered = { - 'default': MeteredType.UNKNOWN, - 'metered': MeteredType.YES, - 'unmetered': MeteredType.NO - }.get(value, MeteredType.UNKNOWN) - self._wifi_manager.set_current_network_metered(metered) - - # TODO: signal for current network metered type when changing networks, this is wrong until you press it once - # TODO: disable when not connected - self._network_metered_btn = BigMultiToggle("network usage", ["default", "metered", "unmetered"], select_callback=network_metered_callback) - self._network_metered_btn.set_enabled(False) - - wifi_button = BigButton("wi-fi") - wifi_button.set_click_callback(lambda: self._switch_to_panel(NetworkPanelType.WIFI)) - - # Main scroller ---------------------------------- - self._scroller = Scroller([ - wifi_button, - self._network_metered_btn, - self._tethering_toggle_btn, - self._tethering_password_btn, - self._ip_address_btn, - ], snap_items=False) - - # Set up back navigation - self.set_back_callback(back_callback) - - def show_event(self): - super().show_event() - self._current_panel = NetworkPanelType.NONE - self._wifi_ui.show_event() - self._scroller.show_event() - - def hide_event(self): - super().hide_event() - self._wifi_ui.hide_event() - - def _on_network_updated(self, networks: list[Network]): - # Update tethering state - tethering_active = self._wifi_manager.is_tethering_active() - # TODO: use real signals (like activated/settings changed, etc.) to speed up re-enabling buttons - self._tethering_toggle_btn.set_enabled(True) - self._network_metered_btn.set_enabled(lambda: not tethering_active and bool(self._wifi_manager.ipv4_address)) - self._tethering_toggle_btn.set_checked(tethering_active) - - # Update IP address - self._ip_address_btn.set_value(self._wifi_manager.ipv4_address or "Not connected") - - # Update network metered - self._network_metered_btn.set_value( - { - MeteredType.UNKNOWN: 'default', - MeteredType.YES: 'metered', - MeteredType.NO: 'unmetered' - }.get(self._wifi_manager.current_network_metered, 'default')) - - def _switch_to_panel(self, panel_type: NetworkPanelType): - self._current_panel = panel_type - - def _render(self, rect: rl.Rectangle): - self._wifi_manager.process_callbacks() - - if self._current_panel == NetworkPanelType.WIFI: - self._wifi_ui.render(rect) - else: - self._scroller.render(rect) diff --git a/selfdrive/ui/mici/layouts/settings/settings.py b/selfdrive/ui/mici/layouts/settings/settings.py index 75238d581a..a452777748 100644 --- a/selfdrive/ui/mici/layouts/settings/settings.py +++ b/selfdrive/ui/mici/layouts/settings/settings.py @@ -10,7 +10,7 @@ from openpilot.selfdrive.ui.mici.layouts.settings.toggles import TogglesLayoutMi from openpilot.selfdrive.ui.mici.layouts.settings.network import NetworkLayoutMici from openpilot.selfdrive.ui.mici.layouts.settings.device import DeviceLayoutMici, PairBigButton from openpilot.selfdrive.ui.mici.layouts.settings.developer import DeveloperLayoutMici -from openpilot.selfdrive.ui.mici.layouts.settings.firehose import FirehoseLayoutMici +from openpilot.selfdrive.ui.mici.layouts.settings.firehose import FirehoseLayout from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.widgets import Widget, NavWidget @@ -67,7 +67,7 @@ class SettingsLayout(NavWidget): PanelType.NETWORK: PanelInfo("Network", NetworkLayoutMici(back_callback=lambda: self._set_current_panel(None))), PanelType.DEVICE: PanelInfo("Device", DeviceLayoutMici(back_callback=lambda: self._set_current_panel(None))), PanelType.DEVELOPER: PanelInfo("Developer", DeveloperLayoutMici(back_callback=lambda: self._set_current_panel(None))), - PanelType.FIREHOSE: PanelInfo("Firehose", FirehoseLayoutMici(back_callback=lambda: self._set_current_panel(None))), + PanelType.FIREHOSE: PanelInfo("Firehose", FirehoseLayout(back_callback=lambda: self._set_current_panel(None))), } self._font_medium = gui_app.font(FontWeight.MEDIUM) diff --git a/selfdrive/ui/mici/onroad/alert_renderer.py b/selfdrive/ui/mici/onroad/alert_renderer.py index b7f0098073..b5f796bb03 100644 --- a/selfdrive/ui/mici/onroad/alert_renderer.py +++ b/selfdrive/ui/mici/onroad/alert_renderer.py @@ -89,10 +89,6 @@ ALERT_CRITICAL_REBOOT = Alert( class AlertRenderer(Widget): def __init__(self): super().__init__() - self.font_regular: rl.Font = gui_app.font(FontWeight.MEDIUM) - self.font_roman: rl.Font = gui_app.font(FontWeight.ROMAN) - self.font_bold: rl.Font = gui_app.font(FontWeight.BOLD) - self.font_display: rl.Font = gui_app.font(FontWeight.DISPLAY) self._alert_text1_label = UnifiedLabel(text="", font_size=ALERT_FONT_BIG, font_weight=FontWeight.DISPLAY, line_height=0.86, letter_spacing=-0.02) @@ -204,11 +200,11 @@ class AlertRenderer(Widget): text_x = self._rect.x + ALERT_MARGIN text_width = self._rect.width - ALERT_MARGIN if icon_side == 'left': - text_x = self._rect.x + self._txt_turn_signal_right.width + 20 * 2 - text_width = self._rect.width - ALERT_MARGIN - self._txt_turn_signal_right.width - 20 * 2 + text_x = self._rect.x + self._txt_turn_signal_right.width + text_width = self._rect.width - ALERT_MARGIN - self._txt_turn_signal_right.width elif icon_side == 'right': text_x = self._rect.x + ALERT_MARGIN - text_width = self._rect.width - ALERT_MARGIN - self._txt_turn_signal_right.width - 20 * 2 + text_width = self._rect.width - ALERT_MARGIN - self._txt_turn_signal_right.width text_rect = rl.Rectangle( text_x, diff --git a/selfdrive/ui/mici/onroad/augmented_road_view.py b/selfdrive/ui/mici/onroad/augmented_road_view.py index 64d57e8958..5fe33a7e48 100644 --- a/selfdrive/ui/mici/onroad/augmented_road_view.py +++ b/selfdrive/ui/mici/onroad/augmented_road_view.py @@ -1,6 +1,7 @@ +import time import numpy as np import pyray as rl -from cereal import car, log +from cereal import messaging, car, log from msgq.visionipc import VisionStreamType from openpilot.selfdrive.ui.ui_state import ui_state, UIStatus from openpilot.selfdrive.ui.mici.onroad import SIDE_PANEL_WIDTH @@ -160,6 +161,9 @@ class AugmentedRoadView(CameraView): self._fade_texture = gui_app.texture("icons_mici/onroad/onroad_fade.png") + # debug + self._pm = messaging.PubMaster(['uiDebug']) + def is_swiping_left(self) -> bool: """Check if currently swiping left (for scroller to disable).""" return self._bookmark_icon.is_swiping_left() @@ -179,6 +183,7 @@ class AugmentedRoadView(CameraView): super()._handle_mouse_release(mouse_pos) def _render(self, _): + start_draw = time.monotonic() self._switch_stream_if_needed(ui_state.sm) # Update calibration before rendering @@ -244,6 +249,11 @@ class AugmentedRoadView(CameraView): rl.draw_rectangle(int(self.rect.x), int(self.rect.y), int(self.rect.width), int(self.rect.height), rl.Color(0, 0, 0, 175)) self._offroad_label.render(self._content_rect) + # publish uiDebug + msg = messaging.new_message('uiDebug') + msg.uiDebug.drawTimeMillis = (time.monotonic() - start_draw) * 1000 + self._pm.send('uiDebug', msg) + def _switch_stream_if_needed(self, sm): if sm['selfdriveState'].experimentalMode and WIDE_CAM in self.available_streams: v_ego = sm['carState'].vEgo diff --git a/selfdrive/ui/mici/onroad/cameraview.py b/selfdrive/ui/mici/onroad/cameraview.py index 0f425b10da..89a4926ce9 100644 --- a/selfdrive/ui/mici/onroad/cameraview.py +++ b/selfdrive/ui/mici/onroad/cameraview.py @@ -107,7 +107,6 @@ else: class CameraView(Widget): def __init__(self, name: str, stream_type: VisionStreamType): super().__init__() - # TODO: implement a receiver and connect thread self._name = name # Primary stream self.client = VisionIpcClient(name, stream_type, conflate=True) @@ -197,7 +196,10 @@ class CameraView(Widget): # Clean up shader if self.shader and self.shader.id: rl.unload_shader(self.shader) + self.shader.id = 0 + self.frame = None + self.available_streams.clear() self.client = None def __del__(self): @@ -234,6 +236,9 @@ class CameraView(Widget): if buffer: self._texture_needs_update = True self.frame = buffer + elif not self.client.is_connected(): + # ensure we clear the displayed frame when the connection is lost + self.frame = None if not self.frame: self._draw_placeholder(rect) diff --git a/selfdrive/ui/mici/onroad/driver_camera_dialog.py b/selfdrive/ui/mici/onroad/driver_camera_dialog.py index f2fa5e8fe8..9adb660d8b 100644 --- a/selfdrive/ui/mici/onroad/driver_camera_dialog.py +++ b/selfdrive/ui/mici/onroad/driver_camera_dialog.py @@ -15,20 +15,27 @@ EventName = log.OnroadEvent.EventName EVENT_TO_INT = EventName.schema.enumerants +class DriverCameraView(CameraView): + def _calc_frame_matrix(self, rect: rl.Rectangle): + base = super()._calc_frame_matrix(rect) + driver_view_ratio = 1.5 + base[0, 0] *= driver_view_ratio + base[1, 1] *= driver_view_ratio + return base + + class DriverCameraDialog(NavWidget): def __init__(self, no_escape=False): super().__init__() - self._camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_DRIVER) - self._original_calc_frame_matrix = self._camera_view._calc_frame_matrix - self._camera_view._calc_frame_matrix = self._calc_driver_frame_matrix + self._camera_view = DriverCameraView("camerad", VisionStreamType.VISION_STREAM_DRIVER) self.driver_state_renderer = DriverStateRenderer(lines=True) self.driver_state_renderer.set_rect(rl.Rectangle(0, 0, 200, 200)) self.driver_state_renderer.load_icons() - self._pm = messaging.PubMaster(['selfdriveState']) + self._pm: messaging.PubMaster | None = None if not no_escape: # TODO: this can grow unbounded, should be given some thought - device.add_interactive_timeout_callback(self.stop_dmonitoringmodeld) - self.set_back_callback(self._dismiss) + device.add_interactive_timeout_callback(lambda: gui_app.set_modal_overlay(None)) + self.set_back_callback(lambda: gui_app.set_modal_overlay(None)) self.set_back_enabled(not no_escape) # Load eye icons @@ -40,26 +47,24 @@ class DriverCameraDialog(NavWidget): self._load_eye_textures() - def stop_dmonitoringmodeld(self): - ui_state.params.put_bool("IsDriverViewEnabled", False) - gui_app.set_modal_overlay(None) - def show_event(self): super().show_event() ui_state.params.put_bool("IsDriverViewEnabled", True) self._publish_alert_sound(None) device.reset_interactive_timeout(300) ui_state.params.remove("DriverTooDistracted") + self._pm = messaging.PubMaster(['selfdriveState']) def hide_event(self): super().hide_event() + ui_state.params.put_bool("IsDriverViewEnabled", False) device.reset_interactive_timeout() def _handle_mouse_release(self, _): ui_state.params.remove("DriverTooDistracted") - def _dismiss(self): - self.stop_dmonitoringmodeld() + def __del__(self): + self.close() def close(self): if self._camera_view: @@ -103,6 +108,9 @@ class DriverCameraDialog(NavWidget): def _publish_alert_sound(self, dm_state): """Publish selfdriveState with only alertSound field set""" + if self._pm is None: + return + msg = messaging.new_message('selfdriveState') if dm_state is not None and len(dm_state.events): event_name = EVENT_TO_INT[dm_state.events[0].name] @@ -221,13 +229,6 @@ class DriverCameraDialog(NavWidget): glasses_prob = driver_data.sunglassesProb rl.draw_texture_v(self._glasses_texture, glasses_pos, rl.Color(70, 80, 161, int(255 * glasses_prob))) - def _calc_driver_frame_matrix(self, rect: rl.Rectangle): - base = self._original_calc_frame_matrix(rect) - driver_view_ratio = 1.5 - base[0, 0] *= driver_view_ratio - base[1, 1] *= driver_view_ratio - return base - if __name__ == "__main__": gui_app.init_window("Driver Camera View (mici)") diff --git a/selfdrive/ui/mici/onroad/driver_state.py b/selfdrive/ui/mici/onroad/driver_state.py index 369055846e..080083c3e2 100644 --- a/selfdrive/ui/mici/onroad/driver_state.py +++ b/selfdrive/ui/mici/onroad/driver_state.py @@ -3,6 +3,7 @@ from collections.abc import Callable import numpy as np import math from cereal import log +from openpilot.system.hardware import PC from openpilot.common.filter_simple import FirstOrderFilter from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.widgets import Widget @@ -217,7 +218,10 @@ class DriverStateRenderer(Widget): rotation = math.degrees(math.atan2(pitch, yaw)) angle_diff = rotation - self._rotation_filter.x angle_diff = ((angle_diff + 180) % 360) - 180 - self._rotation_filter.update(self._rotation_filter.x + angle_diff) + if PC and self._confirm_mode: + self._rotation_filter.x += 2 + else: + self._rotation_filter.update(self._rotation_filter.x + angle_diff) if not self.should_draw: self._fade_filter.update(0.0) diff --git a/selfdrive/ui/mici/onroad/hud_renderer.py b/selfdrive/ui/mici/onroad/hud_renderer.py index bb5171d6e3..7f489ccf98 100644 --- a/selfdrive/ui/mici/onroad/hud_renderer.py +++ b/selfdrive/ui/mici/onroad/hud_renderer.py @@ -30,20 +30,8 @@ class FontSizes: @dataclass(frozen=True) class Colors: - white: rl.Color = rl.WHITE - disengaged: rl.Color = rl.Color(145, 155, 149, 255) - override: rl.Color = rl.Color(145, 155, 149, 255) # Added - engaged: rl.Color = rl.Color(128, 216, 166, 255) - disengaged_bg: rl.Color = rl.Color(0, 0, 0, 153) - override_bg: rl.Color = rl.Color(145, 155, 149, 204) - engaged_bg: rl.Color = rl.Color(128, 216, 166, 204) - grey: rl.Color = rl.Color(166, 166, 166, 255) - dark_grey: rl.Color = rl.Color(114, 114, 114, 255) - black_translucent: rl.Color = rl.Color(0, 0, 0, 166) - white_translucent: rl.Color = rl.Color(255, 255, 255, 200) - border_translucent: rl.Color = rl.Color(255, 255, 255, 75) - header_gradient_start: rl.Color = rl.Color(0, 0, 0, 114) - header_gradient_end: rl.Color = rl.BLANK + WHITE = rl.WHITE + WHITE_TRANSLUCENT = rl.Color(255, 255, 255, 200) FONT_SIZES = FontSizes() @@ -236,16 +224,18 @@ class HudRenderer(Widget): def _draw_set_speed(self, rect: rl.Rectangle) -> None: """Draw the MAX speed indicator box.""" - x = rect.x - y = rect.y - alpha = self._set_speed_alpha_filter.update(0 < rl.get_time() - self._set_speed_changed_time < SET_SPEED_PERSISTENCE and self._can_draw_top_icons and self._engaged) + if alpha < 1e-2: + return + + x = rect.x + y = rect.y # draw drop shadow circle_radius = 162 // 2 rl.draw_circle_gradient(int(x + circle_radius), int(y + circle_radius), circle_radius, - rl.Color(0, 0, 0, int(255 / 2 * alpha)), rl.Color(0, 0, 0, 0)) + rl.Color(0, 0, 0, int(255 / 2 * alpha)), rl.BLANK) set_speed_color = rl.Color(255, 255, 255, int(255 * 0.9 * alpha)) max_color = rl.Color(255, 255, 255, int(255 * 0.9 * alpha)) @@ -279,9 +269,9 @@ class HudRenderer(Widget): speed_text = str(round(self.speed)) speed_text_size = measure_text_cached(self._font_bold, speed_text, FONT_SIZES.current_speed) 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 = 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_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) diff --git a/selfdrive/ui/mici/onroad/torque_bar.py b/selfdrive/ui/mici/onroad/torque_bar.py index 1f6dffe879..d7c9f27a92 100644 --- a/selfdrive/ui/mici/onroad/torque_bar.py +++ b/selfdrive/ui/mici/onroad/torque_bar.py @@ -130,6 +130,9 @@ def arc_bar_pts(cx: float, cy: float, pts = np.vstack((outer, cap_end, inner, cap_start, outer[:1])).astype(np.float32) + # Rotate to start from middle of cap for proper triangulation + pts = np.roll(pts, cap_segs, axis=0) + if DEBUG: n = len(pts) idx = int(time.monotonic() * 12) % max(1, n) # speed: 12 pts/sec diff --git a/selfdrive/ui/mici/widgets/dialog.py b/selfdrive/ui/mici/widgets/dialog.py index d64ab65ef2..b11056f993 100644 --- a/selfdrive/ui/mici/widgets/dialog.py +++ b/selfdrive/ui/mici/widgets/dialog.py @@ -282,7 +282,8 @@ class BigDialogOptionButton(Widget): self._selected = False self._label = UnifiedLabel(option, font_size=70, text_color=rl.Color(255, 255, 255, int(255 * 0.58)), - font_weight=FontWeight.DISPLAY_REGULAR, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_TOP) + font_weight=FontWeight.DISPLAY_REGULAR, alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE, + scroll=True) def set_selected(self, selected: bool): self._selected = selected diff --git a/selfdrive/ui/onroad/cameraview.py b/selfdrive/ui/onroad/cameraview.py index 87db7cc636..5443948465 100644 --- a/selfdrive/ui/onroad/cameraview.py +++ b/selfdrive/ui/onroad/cameraview.py @@ -68,7 +68,6 @@ else: class CameraView(Widget): def __init__(self, name: str, stream_type: VisionStreamType): super().__init__() - # TODO: implement a receiver and connect thread self._name = name # Primary stream self.client = VisionIpcClient(name, stream_type, conflate=True) @@ -337,12 +336,12 @@ class CameraView(Widget): self._initialize_textures() def _initialize_textures(self): - self._clear_textures() - if not TICI: - self.texture_y = rl.load_texture_from_image(rl.Image(None, int(self.client.stride), - int(self.client.height), 1, rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_GRAYSCALE)) - self.texture_uv = rl.load_texture_from_image(rl.Image(None, int(self.client.stride // 2), - int(self.client.height // 2), 1, rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA)) + self._clear_textures() + if not TICI: + self.texture_y = rl.load_texture_from_image(rl.Image(None, int(self.client.stride), + int(self.client.height), 1, rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_GRAYSCALE)) + self.texture_uv = rl.load_texture_from_image(rl.Image(None, int(self.client.stride // 2), + int(self.client.height // 2), 1, rl.PixelFormat.PIXELFORMAT_UNCOMPRESSED_GRAY_ALPHA)) def _clear_textures(self): if self.texture_y and self.texture_y.id: diff --git a/selfdrive/ui/onroad/hud_renderer.py b/selfdrive/ui/onroad/hud_renderer.py index a2459c27e2..79f150deea 100644 --- a/selfdrive/ui/onroad/hud_renderer.py +++ b/selfdrive/ui/onroad/hud_renderer.py @@ -35,20 +35,20 @@ class FontSizes: @dataclass(frozen=True) class Colors: - white: rl.Color = rl.WHITE - disengaged: rl.Color = rl.Color(145, 155, 149, 255) - override: rl.Color = rl.Color(145, 155, 149, 255) # Added - engaged: rl.Color = rl.Color(128, 216, 166, 255) - disengaged_bg: rl.Color = rl.Color(0, 0, 0, 153) - override_bg: rl.Color = rl.Color(145, 155, 149, 204) - engaged_bg: rl.Color = rl.Color(128, 216, 166, 204) - grey: rl.Color = rl.Color(166, 166, 166, 255) - dark_grey: rl.Color = rl.Color(114, 114, 114, 255) - black_translucent: rl.Color = rl.Color(0, 0, 0, 166) - white_translucent: rl.Color = rl.Color(255, 255, 255, 200) - border_translucent: rl.Color = rl.Color(255, 255, 255, 75) - header_gradient_start: rl.Color = rl.Color(0, 0, 0, 114) - header_gradient_end: rl.Color = rl.BLANK + WHITE = rl.WHITE + DISENGAGED = rl.Color(145, 155, 149, 255) + OVERRIDE = rl.Color(145, 155, 149, 255) # Added + ENGAGED = rl.Color(128, 216, 166, 255) + DISENGAGED_BG = rl.Color(0, 0, 0, 153) + OVERRIDE_BG = rl.Color(145, 155, 149, 204) + ENGAGED_BG = rl.Color(128, 216, 166, 204) + GREY = rl.Color(166, 166, 166, 255) + DARK_GREY = rl.Color(114, 114, 114, 255) + BLACK_TRANSLUCENT = rl.Color(0, 0, 0, 166) + WHITE_TRANSLUCENT = rl.Color(255, 255, 255, 200) + BORDER_TRANSLUCENT = rl.Color(255, 255, 255, 75) + HEADER_GRADIENT_START = rl.Color(0, 0, 0, 114) + HEADER_GRADIENT_END = rl.BLANK UI_CONFIG = UIConfig() @@ -108,8 +108,8 @@ class HudRenderer(Widget): int(rect.y), int(rect.width), UI_CONFIG.header_height, - COLORS.header_gradient_start, - COLORS.header_gradient_end, + COLORS.HEADER_GRADIENT_START, + COLORS.HEADER_GRADIENT_END, ) if self.is_cruise_available: @@ -131,19 +131,19 @@ class HudRenderer(Widget): y = rect.y + 45 set_speed_rect = rl.Rectangle(x, y, set_speed_width, UI_CONFIG.set_speed_height) - rl.draw_rectangle_rounded(set_speed_rect, 0.35, 10, COLORS.black_translucent) - rl.draw_rectangle_rounded_lines_ex(set_speed_rect, 0.35, 10, 6, COLORS.border_translucent) + rl.draw_rectangle_rounded(set_speed_rect, 0.35, 10, COLORS.BLACK_TRANSLUCENT) + rl.draw_rectangle_rounded_lines_ex(set_speed_rect, 0.35, 10, 6, COLORS.BORDER_TRANSLUCENT) - max_color = COLORS.grey - set_speed_color = COLORS.dark_grey + max_color = COLORS.GREY + set_speed_color = COLORS.DARK_GREY if self.is_cruise_set: - set_speed_color = COLORS.white + set_speed_color = COLORS.WHITE if ui_state.status == UIStatus.ENGAGED: - max_color = COLORS.engaged + max_color = COLORS.ENGAGED elif ui_state.status == UIStatus.DISENGAGED: - max_color = COLORS.disengaged + max_color = COLORS.DISENGAGED elif ui_state.status == UIStatus.OVERRIDE: - max_color = COLORS.override + max_color = COLORS.OVERRIDE max_text = tr("MAX") max_text_width = measure_text_cached(self._font_semi_bold, max_text, FONT_SIZES.max_speed).x @@ -172,9 +172,9 @@ class HudRenderer(Widget): speed_text = str(round(self.speed)) speed_text_size = measure_text_cached(self._font_bold, speed_text, FONT_SIZES.current_speed) 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 = 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_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) diff --git a/selfdrive/ui/tests/.gitignore b/selfdrive/ui/tests/.gitignore index d926a7ae86..98f2a5e8ce 100644 --- a/selfdrive/ui/tests/.gitignore +++ b/selfdrive/ui/tests/.gitignore @@ -2,3 +2,8 @@ test test_translations test_ui/report_1 test_ui/raylib_report + +diff/*.mp4 +diff/*.html +diff/.coverage +diff/htmlcov/ diff --git a/selfdrive/ui/tests/diff/diff.py b/selfdrive/ui/tests/diff/diff.py new file mode 100755 index 0000000000..be7af5438a --- /dev/null +++ b/selfdrive/ui/tests/diff/diff.py @@ -0,0 +1,201 @@ +#!/usr/bin/env python3 +import os +import sys +import subprocess +import tempfile +import base64 +import webbrowser +import argparse +from pathlib import Path +from openpilot.common.basedir import BASEDIR + +DIFF_OUT_DIR = Path(BASEDIR) / "selfdrive" / "ui" / "tests" / "diff" / "report" + + +def extract_frames(video_path, output_dir): + output_pattern = str(output_dir / "frame_%04d.png") + cmd = ['ffmpeg', '-i', video_path, '-vsync', '0', output_pattern, '-y'] + subprocess.run(cmd, capture_output=True, check=True) + frames = sorted(output_dir.glob("frame_*.png")) + return frames + + +def compare_frames(frame1_path, frame2_path): + result = subprocess.run(['cmp', '-s', frame1_path, frame2_path]) + return result.returncode == 0 + + +def frame_to_data_url(frame_path): + with open(frame_path, 'rb') as f: + data = f.read() + return f"data:image/png;base64,{base64.b64encode(data).decode()}" + + +def create_diff_video(video1, video2, output_path): + """Create a diff video using ffmpeg blend filter with difference mode.""" + print("Creating diff video...") + cmd = ['ffmpeg', '-i', video1, '-i', video2, '-filter_complex', '[0:v]blend=all_mode=difference', '-vsync', '0', '-y', output_path] + subprocess.run(cmd, capture_output=True, check=True) + + +def find_differences(video1, video2): + with tempfile.TemporaryDirectory() as tmpdir: + tmpdir = Path(tmpdir) + + print(f"Extracting frames from {video1}...") + frames1_dir = tmpdir / "frames1" + frames1_dir.mkdir() + frames1 = extract_frames(video1, frames1_dir) + + print(f"Extracting frames from {video2}...") + frames2_dir = tmpdir / "frames2" + frames2_dir.mkdir() + frames2 = extract_frames(video2, frames2_dir) + + if len(frames1) != len(frames2): + print(f"WARNING: Frame count mismatch: {len(frames1)} vs {len(frames2)}") + min_frames = min(len(frames1), len(frames2)) + frames1 = frames1[:min_frames] + frames2 = frames2[:min_frames] + + print(f"Comparing {len(frames1)} frames...") + different_frames = [] + frame_data = [] + + for i, (f1, f2) in enumerate(zip(frames1, frames2, strict=False)): + is_different = not compare_frames(f1, f2) + if is_different: + different_frames.append(i) + + if i < 10 or i >= len(frames1) - 10 or is_different: + frame_data.append({'index': i, 'different': is_different, 'frame1_url': frame_to_data_url(f1), 'frame2_url': frame_to_data_url(f2)}) + + return different_frames, frame_data, len(frames1) + + +def generate_html_report(video1, video2, basedir, different_frames, frame_data, total_frames): + chunks = [] + if different_frames: + current_chunk = [different_frames[0]] + for i in range(1, len(different_frames)): + if different_frames[i] == different_frames[i - 1] + 1: + current_chunk.append(different_frames[i]) + else: + chunks.append(current_chunk) + current_chunk = [different_frames[i]] + chunks.append(current_chunk) + + result_text = ( + f"✅ Videos are identical! ({total_frames} frames)" + if len(different_frames) == 0 + else f"❌ Found {len(different_frames)} different frames out of {total_frames} total ({(len(different_frames) / total_frames * 100):.1f}%)" + ) + + html = f"""

UI Diff

+ + + + + + +
+

Video 1

+ +
+

Video 2

+ +
+

Pixel Diff

+ +
+ +
+

Results: {result_text}

+""" + return html + + +def main(): + parser = argparse.ArgumentParser(description='Compare two videos and generate HTML diff report') + parser.add_argument('video1', help='First video file') + parser.add_argument('video2', help='Second video file') + parser.add_argument('output', nargs='?', default='diff.html', help='Output HTML file (default: diff.html)') + parser.add_argument("--basedir", type=str, help="Base directory for output", default="") + parser.add_argument('--no-open', action='store_true', help='Do not open HTML report in browser') + + args = parser.parse_args() + + os.makedirs(DIFF_OUT_DIR, exist_ok=True) + + print("=" * 60) + print("VIDEO DIFF - HTML REPORT") + print("=" * 60) + print(f"Video 1: {args.video1}") + print(f"Video 2: {args.video2}") + print(f"Output: {args.output}") + print() + + # Create diff video + diff_video_path = os.path.join(os.path.dirname(args.output), DIFF_OUT_DIR / "diff.mp4") + create_diff_video(args.video1, args.video2, diff_video_path) + + different_frames, frame_data, total_frames = find_differences(args.video1, args.video2) + + if different_frames is None: + sys.exit(1) + + print() + print("Generating HTML report...") + html = generate_html_report(args.video1, args.video2, args.basedir, different_frames, frame_data, total_frames) + + with open(DIFF_OUT_DIR / args.output, 'w') as f: + f.write(html) + + # Open in browser by default + if not args.no_open: + print(f"Opening {args.output} in browser...") + webbrowser.open(f'file://{os.path.abspath(DIFF_OUT_DIR / args.output)}') + + return 0 if len(different_frames) == 0 else 1 + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/selfdrive/ui/tests/diff/replay.py b/selfdrive/ui/tests/diff/replay.py new file mode 100755 index 0000000000..9da157660e --- /dev/null +++ b/selfdrive/ui/tests/diff/replay.py @@ -0,0 +1,128 @@ +#!/usr/bin/env python3 +import os +import time +import coverage +import pyray as rl +from dataclasses import dataclass +from openpilot.selfdrive.ui.tests.diff.diff import DIFF_OUT_DIR + +os.environ["RECORD"] = "1" +if "RECORD_OUTPUT" not in os.environ: + os.environ["RECORD_OUTPUT"] = "mici_ui_replay.mp4" + +os.environ["RECORD_OUTPUT"] = os.path.join(DIFF_OUT_DIR, os.environ["RECORD_OUTPUT"]) + +from openpilot.common.params import Params +from openpilot.system.version import terms_version, training_version +from openpilot.system.ui.lib.application import gui_app, MousePos, MouseEvent +from openpilot.selfdrive.ui.ui_state import ui_state +from openpilot.selfdrive.ui.mici.layouts.main import MiciMainLayout + +FPS = 60 +HEADLESS = os.getenv("WINDOWED", "0") == "1" + + +@dataclass +class DummyEvent: + click: bool = False + # TODO: add some kind of intensity + swipe_left: bool = False + swipe_right: bool = False + swipe_down: bool = False + + +SCRIPT = [ + (0, DummyEvent()), + (FPS * 1, DummyEvent(click=True)), + (FPS * 2, DummyEvent(click=True)), + (FPS * 3, DummyEvent()), +] + + +def setup_state(): + params = Params() + params.put("HasAcceptedTerms", terms_version) + params.put("CompletedTrainingVersion", training_version) + params.put("DongleId", "test123456789") + params.put("UpdaterCurrentDescription", "0.10.1 / test-branch / abc1234 / Nov 30") + return None + + +def inject_click(coords): + events = [] + x, y = coords[0] + events.append(MouseEvent(pos=MousePos(x, y), slot=0, left_pressed=True, left_released=False, left_down=False, t=time.monotonic())) + for x, y in coords[1:]: + events.append(MouseEvent(pos=MousePos(x, y), slot=0, left_pressed=False, left_released=False, left_down=True, t=time.monotonic())) + x, y = coords[-1] + events.append(MouseEvent(pos=MousePos(x, y), slot=0, left_pressed=False, left_released=True, left_down=False, t=time.monotonic())) + + with gui_app._mouse._lock: + gui_app._mouse._events.extend(events) + + +def handle_event(event: DummyEvent): + if event.click: + inject_click([(gui_app.width // 2, gui_app.height // 2)]) + if event.swipe_left: + inject_click([(gui_app.width * 3 // 4, gui_app.height // 2), + (gui_app.width // 4, gui_app.height // 2), + (0, gui_app.height // 2)]) + if event.swipe_right: + inject_click([(gui_app.width // 4, gui_app.height // 2), + (gui_app.width * 3 // 4, gui_app.height // 2), + (gui_app.width, gui_app.height // 2)]) + if event.swipe_down: + inject_click([(gui_app.width // 2, gui_app.height // 4), + (gui_app.width // 2, gui_app.height * 3 // 4), + (gui_app.width // 2, gui_app.height)]) + + +def run_replay(): + setup_state() + os.makedirs(DIFF_OUT_DIR, exist_ok=True) + + if not HEADLESS: + rl.set_config_flags(rl.FLAG_WINDOW_HIDDEN) + gui_app.init_window("ui diff test", fps=FPS) + main_layout = MiciMainLayout() + main_layout.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) + + frame = 0 + script_index = 0 + + for should_render in gui_app.render(): + while script_index < len(SCRIPT) and SCRIPT[script_index][0] == frame: + _, event = SCRIPT[script_index] + handle_event(event) + script_index += 1 + + ui_state.update() + + if should_render: + main_layout.render() + + frame += 1 + + if script_index >= len(SCRIPT): + break + + gui_app.close() + + print(f"Total frames: {frame}") + print(f"Video saved to: {os.environ['RECORD_OUTPUT']}") + + +def main(): + cov = coverage.coverage(source=['openpilot.selfdrive.ui.mici']) + with cov.collect(): + run_replay() + cov.stop() + cov.save() + cov.report() + cov.html_report(directory=os.path.join(DIFF_OUT_DIR, 'htmlcov')) + print("HTML report: htmlcov/index.html") + + +if __name__ == "__main__": + main() diff --git a/selfdrive/ui/tests/profile_onroad.py b/selfdrive/ui/tests/profile_onroad.py index b1fa4acc48..fde4f25ffe 100755 --- a/selfdrive/ui/tests/profile_onroad.py +++ b/selfdrive/ui/tests/profile_onroad.py @@ -88,9 +88,9 @@ if __name__ == "__main__": print("Running...") patch_submaster(message_chunks) - W, H = 1928, 1208 + W, H = 2048, 1216 vipc = VisionIpcServer("camerad") - vipc.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 5, 1928, 1208) + vipc.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 5, W, H) vipc.start_listener() yuv_buffer_size = W * H + (W // 2) * (H // 2) * 2 yuv_data = np.random.randint(0, 256, yuv_buffer_size, dtype=np.uint8).tobytes() diff --git a/selfdrive/ui/translations/app_ko.po b/selfdrive/ui/translations/app_ko.po index 5a3e891b87..f12aebaeb3 100644 --- a/selfdrive/ui/translations/app_ko.po +++ b/selfdrive/ui/translations/app_ko.po @@ -68,10 +68,10 @@ msgid "" "control alpha. Changing this setting will restart openpilot if the car is " "powered on." msgstr "" -"경고: 이 차량에서 openpilot의 종방향 제어는 알파 버전이며 자동 긴급 제동" -"(AEB)을 비활성화합니다.

이 차량에서는 openpilot 종방향 제어 대신 " -"차량 내장 ACC가 기본으로 사용됩니다. openpilot 종방향 제어로 전환하려면 이 설" -"정을 켜세요. 종방향 제어 알파를 켤 때는 실험 모드 사용을 권장합니다. 차량 전" +"경고: 이 차량에서 openpilot의 롱컨 제어는 알파 버전이며 자동 긴급 제동" +"(AEB)을 비활성화합니다.

이 차량에서는 openpilot 롱컨 제어 대신 " +"차량 내장 ACC가 기본으로 사용됩니다. openpilot 롱컨 제어로 전환하려면 이 설" +"정을 켜세요. 롱컨 제어 알파를 켤 때는 실험 모드 사용을 권장합니다. 차량 전" "원이 켜져 있는 경우 이 설정을 변경하면 openpilot이 재시작됩니다." #: selfdrive/ui/layouts/settings/device.py:148 @@ -130,7 +130,7 @@ msgstr "동의" #: selfdrive/ui/layouts/settings/toggles.py:70 #, python-format msgid "Always-On Driver Monitoring" -msgstr "항상 켜짐 운전자 모니터링" +msgstr "운전자 모니터링 항상 켜짐" #: selfdrive/ui/layouts/settings/toggles.py:186 #, python-format @@ -138,7 +138,7 @@ msgid "" "An alpha version of openpilot longitudinal control can be tested, along with " "Experimental mode, on non-release branches." msgstr "" -"openpilot 종방향 제어 알파 버전은 실험 모드와 함께 비릴리스 브랜치에서 테스트" +"openpilot 롱컨 제어 알파 버전은 실험 모드와 함께 비릴리스 브랜치에서 테스트" "할 수 있습니다." #: selfdrive/ui/layouts/settings/device.py:187 @@ -192,7 +192,7 @@ msgstr "확인" #: selfdrive/ui/widgets/exp_mode_button.py:50 #, python-format msgid "CHILL MODE ON" -msgstr "칠 모드 켜짐" +msgstr "안정적 모드 켜짐" #: system/ui/widgets/network.py:155 selfdrive/ui/layouts/sidebar.py:73 #: selfdrive/ui/layouts/sidebar.py:134 selfdrive/ui/layouts/sidebar.py:136 @@ -283,7 +283,7 @@ msgstr "해제 후 재시작" #: selfdrive/ui/layouts/settings/device.py:103 #, python-format msgid "Disengage to Reset Calibration" -msgstr "해제 후 보정 재설정" +msgstr "해제 후 캘리브레이션 재설정" #: selfdrive/ui/layouts/settings/toggles.py:32 msgid "Display speed in km/h instead of mph." @@ -372,7 +372,7 @@ msgstr "openpilot 사용" msgid "" "Enable the openpilot longitudinal control (alpha) toggle to allow " "Experimental mode." -msgstr "실험 모드를 사용하려면 openpilot 종방향 제어(알파) 토글을 켜세요." +msgstr "실험 모드를 사용하려면 openpilot 롱컨 제어(알파) 토글을 켜세요." #: system/ui/widgets/network.py:204 #, python-format @@ -415,7 +415,7 @@ msgid "" "Experimental mode is currently unavailable on this car since the car's stock " "ACC is used for longitudinal control." msgstr "" -"이 차량은 종방향 제어에 순정 ACC를 사용하므로 현재 실험 모드를 사용할 수 없습" +"이 차량은 롱컨 제어에 순정 ACC를 사용하므로 현재 실험 모드를 사용할 수 없습" "니다." #: system/ui/widgets/network.py:373 @@ -430,11 +430,11 @@ msgstr "설정 완료" #: selfdrive/ui/layouts/settings/settings.py:66 msgid "Firehose" -msgstr "Firehose" +msgstr "파이어호스" #: selfdrive/ui/layouts/settings/firehose.py:18 msgid "Firehose Mode" -msgstr "Firehose 모드" +msgstr "파이어호스 모드" #: selfdrive/ui/layouts/settings/firehose.py:25 msgid "" @@ -462,7 +462,7 @@ msgstr "" "최대의 효과를 위해 주 1회는 장치를 실내로 가져와 품질 좋은 USB‑C 어댑터와 " "Wi‑Fi에 연결하세요.\n" "\n" -"핫스팟이나 무제한 SIM에 연결되어 있다면 주행 중에도 Firehose 모드가 동작합니" +"핫스팟이나 무제한 SIM에 연결되어 있다면 주행 중에도 파이어호스 모드가 동작합니" "다.\n" "\n" "\n" @@ -470,7 +470,7 @@ msgstr "" "\n" "어떻게, 어디서 운전하는지가 중요한가요? 아니요. 평소처럼 운전하세요.\n" "\n" -"Firehose 모드에서 모든 세그먼트가 가져가지나요? 아니요. 일부 세그먼트만 선택" +"파이어호스 모드에서 모든 구간을 가져가지나요? 아니요. 일부 구간만 선택" "적으로 가져갑니다.\n" "\n" "좋은 USB‑C 어댑터는 무엇인가요? 빠른 휴대폰 또는 노트북 충전기면 충분합니" @@ -544,7 +544,7 @@ msgstr "LTE" #: selfdrive/ui/layouts/settings/developer.py:64 #, python-format msgid "Longitudinal Maneuver Mode" -msgstr "종방향 매뉴버 모드" +msgstr "롱컨 기동 모드" #: selfdrive/ui/onroad/hud_renderer.py:148 #, python-format @@ -623,7 +623,7 @@ msgstr "미리보기" #: selfdrive/ui/widgets/prime.py:44 #, python-format msgid "PRIME FEATURES:" -msgstr "prime 기능:" +msgstr "프라임 기능:" #: selfdrive/ui/layouts/settings/device.py:48 #, python-format @@ -646,7 +646,7 @@ msgid "" "Pair your device with comma connect (connect.comma.ai) and claim your comma " "prime offer." msgstr "" -"장치를 comma connect(connect.comma.ai)와 페어링하고 comma prime 혜택을 받으세" +"장치를 comma connect(connect.comma.ai)와 페어링하고 comma 프라임 혜택을 받으세" "요." #: selfdrive/ui/widgets/setup.py:91 @@ -748,7 +748,7 @@ msgstr "규제 정보" #: selfdrive/ui/layouts/settings/toggles.py:98 #, python-format msgid "Relaxed" -msgstr "편안함" +msgstr "편안한" #: selfdrive/ui/widgets/prime.py:47 #, python-format @@ -773,7 +773,7 @@ msgstr "재설정" #: selfdrive/ui/layouts/settings/device.py:51 #, python-format msgid "Reset Calibration" -msgstr "보정 재설정" +msgstr "캘리브레이션 재설정" #: selfdrive/ui/layouts/settings/device.py:65 #, python-format @@ -841,7 +841,7 @@ msgid "" "cycle through these personalities with your steering wheel distance button." msgstr "" "표준을 권장합니다. 공격적 모드에서는 앞차를 더 가깝게 따라가고 가감속이 더 적" -"극적입니다. 편안함 모드에서는 앞차와 거리를 더 둡니다. 지원 차량에서는 스티어" +"극적입니다. 편안한 모드에서는 앞차와 거리를 더 둡니다. 지원 차량에서는 스티어" "링의 차간 버튼으로 이 성향들을 전환할 수 있습니다." #: selfdrive/ui/onroad/alert_renderer.py:59 @@ -892,7 +892,7 @@ msgstr "제거" #: selfdrive/ui/layouts/sidebar.py:117 msgid "Unknown" -msgstr "알 수 없음" +msgstr "알수없음" #: selfdrive/ui/layouts/settings/software.py:48 #, python-format @@ -994,7 +994,7 @@ msgstr "카메라 시작 중" #: selfdrive/ui/widgets/prime.py:63 #, python-format msgid "comma prime" -msgstr "comma prime" +msgstr "comma 프라임" #: system/ui/widgets/network.py:142 #, python-format @@ -1054,7 +1054,7 @@ msgstr "지금" #: selfdrive/ui/layouts/settings/developer.py:71 #, python-format msgid "openpilot Longitudinal Control (Alpha)" -msgstr "openpilot 종방향 제어(알파)" +msgstr "openpilot 롱컨 제어(알파)" #: selfdrive/ui/onroad/alert_renderer.py:51 #, python-format @@ -1076,9 +1076,9 @@ msgid "" "some turns. The Experimental mode logo will also be shown in the top right " "corner." msgstr "" -"openpilot은 기본적으로 칠 모드로 주행합니다. 실험 모드를 사용하면 칠 모드에 " +"openpilot은 기본적으로 안정적 모드로 주행합니다. 실험 모드를 사용하면 안정적 모드에 " "아직 준비되지 않은 알파 수준의 기능이 활성화됩니다. 실험 기능은 아래와 같습니" -"다:

엔드투엔드 종방향 제어


주행 모델이 가속과 제동을 제어합니" +"다:

엔드투엔드 롱컨 제어


주행 모델이 가속과 제동을 제어합니" "다. openpilot은 빨간 신호 및 정지 표지에서의 정지를 포함해 사람이 운전한다고 " "판단하는 방식으로 주행합니다. 주행 속도는 모델이 결정하므로 설정 속도는 상한" "으로만 동작합니다. 알파 품질 기능이므로 오작동이 발생할 수 있습니다.

" @@ -1111,7 +1111,7 @@ msgstr "" #: selfdrive/ui/layouts/settings/toggles.py:183 #, python-format msgid "openpilot longitudinal control may come in a future update." -msgstr "openpilot 종방향 제어는 향후 업데이트에서 제공될 수 있습니다." +msgstr "openpilot 롱컨 제어는 향후 업데이트에서 제공될 수 있습니다." #: selfdrive/ui/layouts/settings/device.py:26 msgid "" @@ -1177,7 +1177,7 @@ msgstr[0] "{}분 전" #, python-format msgid "{} segment of your driving is in the training dataset so far." msgid_plural "{} segments of your driving is in the training dataset so far." -msgstr[0] "현재까지 귀하의 주행 {}세그먼트가 학습 데이터셋에 포함되었습니다." +msgstr[0] "현재까지 귀하의 주행 {}구간이 학습 데이터셋에 포함되었습니다." #: selfdrive/ui/widgets/prime.py:62 #, python-format @@ -1187,4 +1187,4 @@ msgstr "✓ 구독됨" #: selfdrive/ui/widgets/setup.py:22 #, python-format msgid "🔥 Firehose Mode 🔥" -msgstr "🔥 Firehose 모드 🔥" +msgstr "🔥 파이어호스 모드 🔥" diff --git a/selfdrive/ui/translations/app_uk.po b/selfdrive/ui/translations/app_uk.po new file mode 100644 index 0000000000..cf78fb5a33 --- /dev/null +++ b/selfdrive/ui/translations/app_uk.po @@ -0,0 +1,1258 @@ +# Ukrainian translations for PACKAGE package. +# Copyright (C) 2025 THE PACKAGE'S COPYRIGHT HOLDER +# This file is distributed under the same license as the PACKAGE package. +# Automatically generated, 2025. +# +msgid "" +msgstr "" +"Project-Id-Version: \n" +"Report-Msgid-Bugs-To: \n" +"POT-Creation-Date: 2025-11-19 12:21+0200\n" +"PO-Revision-Date: 2025-11-19 13:27+0200\n" +"Last-Translator: KeeFeeRe \n" +"Language-Team: none\n" +"Language: uk\n" +"MIME-Version: 1.0\n" +"Content-Type: text/plain; charset=UTF-8\n" +"Content-Transfer-Encoding: 8bit\n" +"Plural-Forms: nplurals=3; plural=(n%10==1 && n%100!=11 ? 0 : n%10>=2 && " +"n%10<=4 && (n%100<10 || n%100>=20) ? 1 : 2);\n" +"X-Generator: Poedit 3.8\n" + +#: selfdrive/ui/layouts/settings/device.py:160 +#, python-format +msgid " Steering torque response calibration is complete." +msgstr " Калібрування реакції крутного моменту керма завершено." + +#: selfdrive/ui/layouts/settings/device.py:158 +#, python-format +msgid " Steering torque response calibration is {}% complete." +msgstr "Калібрування реакції крутного моменту керма завершено на {}%." + +#: selfdrive/ui/layouts/settings/device.py:133 +#, python-format +msgid " Your device is pointed {:.1f}° {} and {:.1f}° {}." +msgstr " Ваш пристрій нахилено на {:.1f}° {} та {:.1f}° {}." + +#: selfdrive/ui/layouts/sidebar.py:43 +msgid "--" +msgstr "--" + +#: selfdrive/ui/widgets/prime.py:47 +#, python-format +msgid "1 year of drive storage" +msgstr "1 рік зберігання поїздок" + +#: selfdrive/ui/widgets/prime.py:47 +#, python-format +msgid "24/7 LTE connectivity" +msgstr "Підключення LTE 24/7" + +#: selfdrive/ui/layouts/sidebar.py:46 +msgid "2G" +msgstr "2G" + +#: selfdrive/ui/layouts/sidebar.py:47 +msgid "3G" +msgstr "3G" + +#: selfdrive/ui/layouts/sidebar.py:49 +msgid "5G" +msgstr "5G" + +#: selfdrive/ui/layouts/settings/developer.py:23 +msgid "" +"WARNING: openpilot longitudinal control is in alpha for this car and will " +"disable Automatic Emergency Braking (AEB).

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. Changing this setting will restart openpilot if the car is " +"powered on." +msgstr "" +"ПОПЕРЕДЖЕННЯ: поздовжнє керування openpilot для цього автомобіля знаходиться " +"в стадії альфа-тестування і вимкне автоматичне екстрене гальмування (AEB)." + +#: selfdrive/ui/layouts/settings/device.py:148 +#, python-format +msgid "

Steering lag calibration is complete." +msgstr "

Калібрування затримки кермування завершено." + +#: selfdrive/ui/layouts/settings/device.py:146 +#, python-format +msgid "

Steering lag calibration is {}% complete." +msgstr "

Калібрування затримки кермування завершено на {}%." + +#: selfdrive/ui/layouts/settings/firehose.py:138 +#, python-format +msgid "ACTIVE" +msgstr "АКТИВНИЙ" + +#: selfdrive/ui/layouts/settings/developer.py:15 +msgid "" +"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." +msgstr "" +"ADB (Android Debug Bridge) дозволяє підключатися до вашого пристрою через " +"USB або мережу. Дивіться https://docs.comma.ai/how-to/connect-to-comma для " +"отримання додаткової інформації." + +#: selfdrive/ui/widgets/ssh_key.py:30 +msgid "ADD" +msgstr "ДОДАТИ" + +#: system/ui/widgets/network.py:139 +#, python-format +msgid "APN Setting" +msgstr "Налаштування APN" + +#: selfdrive/ui/widgets/offroad_alerts.py:109 +#, python-format +msgid "Acknowledge Excessive Actuation" +msgstr "Визнайте надмірне спрацьовування" + +#: system/ui/widgets/network.py:74 system/ui/widgets/network.py:95 +#, python-format +msgid "Advanced" +msgstr "Розширені" + +#: selfdrive/ui/layouts/settings/toggles.py:98 +#, python-format +msgid "Aggressive" +msgstr "Агресивн." + +#: selfdrive/ui/layouts/onboarding.py:116 +#, python-format +msgid "Agree" +msgstr "Погодитися" + +#: selfdrive/ui/layouts/settings/toggles.py:70 +#, python-format +msgid "Always-On Driver Monitoring" +msgstr "Постійний моніторинг водія" + +#: selfdrive/ui/layouts/settings/toggles.py:186 +#, python-format +msgid "" +"An alpha version of openpilot longitudinal control can be tested, along with " +"Experimental mode, on non-release branches." +msgstr "" +"Альфа-версію поздовжнього керування openpilot можна протестувати разом з " +"експериментальним режимом на нерелізних гілках." + +#: selfdrive/ui/layouts/settings/device.py:187 +#, python-format +msgid "Are you sure you want to power off?" +msgstr "Ви впевнені, що хочете вимкнути?" + +#: selfdrive/ui/layouts/settings/device.py:175 +#, python-format +msgid "Are you sure you want to reboot?" +msgstr "Ви впевнені, що хочете перезавантажити?" + +#: selfdrive/ui/layouts/settings/device.py:119 +#, python-format +msgid "Are you sure you want to reset calibration?" +msgstr "Ви впевнені, що хочете скинути калібрування?" + +#: selfdrive/ui/layouts/settings/software.py:171 +#, python-format +msgid "Are you sure you want to uninstall?" +msgstr "Ви впевнені, що хочете видалити?" + +#: system/ui/widgets/network.py:99 +#: selfdrive/ui/layouts/onboarding.py:147 +#, python-format +msgid "Back" +msgstr "Назад" + +#: selfdrive/ui/widgets/prime.py:38 +#, python-format +msgid "Become a comma prime member at connect.comma.ai" +msgstr "Станьте членом comma prime на connect.comma.ai" + +#: selfdrive/ui/widgets/pairing_dialog.py:119 +#, python-format +msgid "Bookmark connect.comma.ai to your home screen to use it like an app" +msgstr "" +"Додайте connect.comma.ai до головного екрану, щоб використовувати його як " +"додаток." + +#: selfdrive/ui/layouts/settings/device.py:68 +#, python-format +msgid "CHANGE" +msgstr "ЗМІНИТИ" + +#: selfdrive/ui/layouts/settings/software.py:50 +#: selfdrive/ui/layouts/settings/software.py:115 +#: selfdrive/ui/layouts/settings/software.py:126 +#: selfdrive/ui/layouts/settings/software.py:155 +#, python-format +msgid "CHECK" +msgstr "ПЕРЕВІРИТИ" + +#: selfdrive/ui/widgets/exp_mode_button.py:50 +#, python-format +msgid "CHILL MODE ON" +msgstr "СПОКІЙНИЙ РЕЖИМ" + +#: system/ui/widgets/network.py:155 +#: selfdrive/ui/layouts/sidebar.py:73 +#: selfdrive/ui/layouts/sidebar.py:134 +#: selfdrive/ui/layouts/sidebar.py:136 +#: selfdrive/ui/layouts/sidebar.py:138 +#, python-format +msgid "CONNECT" +msgstr "CONNECT" + +#: system/ui/widgets/network.py:369 +#, python-format +msgid "CONNECTING..." +msgstr "ПІДКЛЮЧА..." + +#: system/ui/widgets/confirm_dialog.py:23 system/ui/widgets/option_dialog.py:35 +#: system/ui/widgets/network.py:318 system/ui/widgets/keyboard.py:81 +#, python-format +msgid "Cancel" +msgstr "Скасувати" + +#: system/ui/widgets/network.py:134 +#, python-format +msgid "Cellular Metered" +msgstr "Лімітне стільникове з'єднання" + +#: selfdrive/ui/layouts/settings/device.py:68 +#, python-format +msgid "Change Language" +msgstr "Змінити мову" + +#: selfdrive/ui/layouts/settings/toggles.py:125 +#, python-format +msgid "Changing this setting will restart openpilot if the car is powered on." +msgstr "" +"Зміна цього параметра призведе до перезапуску openpilot, якщо автомобіль " +"увімкнено." + +#: selfdrive/ui/widgets/pairing_dialog.py:118 +#, python-format +msgid "Click \"add new device\" and scan the QR code on the right" +msgstr "Натисніть «додати новий пристрій» і відскануйте QR-код праворуч." + +#: selfdrive/ui/widgets/offroad_alerts.py:104 +#, python-format +msgid "Close" +msgstr "Закрити" + +#: selfdrive/ui/layouts/settings/software.py:49 +#, python-format +msgid "Current Version" +msgstr "Поточна версія" + +#: selfdrive/ui/layouts/settings/software.py:118 +#, python-format +msgid "DOWNLOAD" +msgstr "ВАНТАЖ" + +#: selfdrive/ui/layouts/onboarding.py:115 +#, python-format +msgid "Decline" +msgstr "Відхилити" + +#: selfdrive/ui/layouts/onboarding.py:148 +#, python-format +msgid "Decline, uninstall openpilot" +msgstr "Відхилити, видалити openpilot" + +#: selfdrive/ui/layouts/settings/settings.py:64 +msgid "Developer" +msgstr "Розробник" + +#: selfdrive/ui/layouts/settings/settings.py:59 +msgid "Device" +msgstr "Пристрій" + +#: selfdrive/ui/layouts/settings/toggles.py:58 +#, python-format +msgid "Disengage on Accelerator Pedal" +msgstr "Вимкнення при натисканні на педаль газу" + +#: selfdrive/ui/layouts/settings/device.py:184 +#, python-format +msgid "Disengage to Power Off" +msgstr "Вимкніть openpilot, щоб вимкнути пристрій" + +#: selfdrive/ui/layouts/settings/device.py:172 +#, python-format +msgid "Disengage to Reboot" +msgstr "Вимкніть openpilot, щоб перезавантажити" + +#: selfdrive/ui/layouts/settings/device.py:103 +#, python-format +msgid "Disengage to Reset Calibration" +msgstr "Деактивуйте для скидання калібрування" + +#: selfdrive/ui/layouts/settings/toggles.py:32 +msgid "Display speed in km/h instead of mph." +msgstr "Відображати швидкість у км/год замість миль/год." + +#: selfdrive/ui/layouts/settings/device.py:59 +#, python-format +msgid "Dongle ID" +msgstr "ID ключа" + +#: selfdrive/ui/layouts/settings/software.py:50 +#, python-format +msgid "Download" +msgstr "Завантажити" + +#: selfdrive/ui/layouts/settings/device.py:62 +#, python-format +msgid "Driver Camera" +msgstr "Камера водія" + +#: selfdrive/ui/layouts/settings/toggles.py:96 +#, python-format +msgid "Driving Personality" +msgstr "Стиль водіння" + +#: system/ui/widgets/network.py:123 system/ui/widgets/network.py:139 +#, python-format +msgid "EDIT" +msgstr "РЕДАГ." + +#: selfdrive/ui/layouts/sidebar.py:138 +msgid "ERROR" +msgstr "ПОМИЛКА" + +#: selfdrive/ui/layouts/sidebar.py:45 +msgid "ETH" +msgstr "ETH" + +#: selfdrive/ui/widgets/exp_mode_button.py:50 +#, python-format +msgid "EXPERIMENTAL MODE ON" +msgstr "ЕКСПЕРИМЕНТ. РЕЖИМ" + +#: selfdrive/ui/layouts/settings/toggles.py:228 +#: selfdrive/ui/layouts/settings/developer.py:166 +#, python-format +msgid "Enable" +msgstr "Увімкнути" + +#: selfdrive/ui/layouts/settings/developer.py:39 +#, python-format +msgid "Enable ADB" +msgstr "Увімкнути ADB" + +#: selfdrive/ui/layouts/settings/toggles.py:64 +#, python-format +msgid "Enable Lane Departure Warnings" +msgstr "Увімкнути попередження про виїзд зі смуги" + +#: system/ui/widgets/network.py:129 +#, python-format +msgid "Enable Roaming" +msgstr "Увімкнути роумінг" + +#: selfdrive/ui/layouts/settings/developer.py:48 +#, python-format +msgid "Enable SSH" +msgstr "Увімкнути SSH" + +#: system/ui/widgets/network.py:120 +#, python-format +msgid "Enable Tethering" +msgstr "Увімкнути точку доступу" + +#: selfdrive/ui/layouts/settings/toggles.py:30 +msgid "Enable driver monitoring even when openpilot is not engaged." +msgstr "Увімкнути моніторинг водія, навіть коли openpilot не ввімкнено." + +#: selfdrive/ui/layouts/settings/toggles.py:46 +#, python-format +msgid "Enable openpilot" +msgstr "Увімкнути openpilot" + +#: selfdrive/ui/layouts/settings/toggles.py:189 +#, python-format +msgid "" +"Enable the openpilot longitudinal control (alpha) toggle to allow " +"Experimental mode." +msgstr "" +"Увімкніть перемикач поздовжнього керування openpilot (альфа), щоб увімкнути " +"експериментальний режим." + +#: system/ui/widgets/network.py:204 +#, python-format +msgid "Enter APN" +msgstr "Введіть APN" + +#: system/ui/widgets/network.py:241 +#, python-format +msgid "Enter SSID" +msgstr "Введіть SSID" + +#: system/ui/widgets/network.py:254 +#, python-format +msgid "Enter new tethering password" +msgstr "Введіть новий пароль для модему" + +#: system/ui/widgets/network.py:237 system/ui/widgets/network.py:314 +#, python-format +msgid "Enter password" +msgstr "Введіть пароль" + +#: selfdrive/ui/widgets/ssh_key.py:89 +#, python-format +msgid "Enter your GitHub username" +msgstr "Введіть ваш логін GitHub" + +#: system/ui/widgets/list_view.py:123 system/ui/widgets/list_view.py:160 +#, python-format +msgid "Error" +msgstr "Помилка" + +#: selfdrive/ui/layouts/settings/toggles.py:52 +#, python-format +msgid "Experimental Mode" +msgstr "Експериментальний режим" + +#: selfdrive/ui/layouts/settings/toggles.py:181 +#, python-format +msgid "" +"Experimental mode is currently unavailable on this car since the car's stock " +"ACC is used for longitudinal control." +msgstr "" +"Експериментальний режим наразі недоступний для цього автомобіля, оскільки " +"для поздовжнього керування використовується штатний адаптивний круїз-" +"контроль (ACC)." + +#: system/ui/widgets/network.py:373 +#, python-format +msgid "FORGETTING..." +msgstr "ЗАБУВАЮ..." + +#: selfdrive/ui/widgets/setup.py:44 +#, python-format +msgid "Finish Setup" +msgstr "Завершити налаштування" + +#: selfdrive/ui/layouts/settings/settings.py:63 +msgid "Firehose" +msgstr "Злива" + +#: selfdrive/ui/layouts/settings/firehose.py:18 +msgid "Firehose Mode" +msgstr "Режим зливи" + +#: selfdrive/ui/layouts/settings/firehose.py:25 +msgid "" +"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" +"\n" +"Frequently Asked Questions\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" +"What's a good USB-C adapter? Any fast phone or laptop charger should be " +"fine.\n" +"\n" +"Does it matter which software I run? Yes, only upstream openpilot (and " +"particular forks) are able to be used for training." +msgstr "" +"Для максимальної ефективності щотижня заносьте пристрій у приміщення та " +"підключайте його до якісного адаптера USB-C і Wi-Fi.\n" +"\n" +"Режим Зливи також може працювати під час руху, якщо пристрій підключено до " +"точки доступу або SIM-картки з необмеженим трафіком.\n" +"\n" +"\n" +"Поширені запитання\n" +"\n" +"Чи має значення, як і де я їду? Ні, просто їдьте, як зазвичай.\n" +"\n" +"Чи всі мої сегменти потрапляють у режим Зливи? Ні, ми вибірково вибираємо " +"підмножину ваших сегментів.\n" +"\n" +"Що таке хороший адаптер USB-C? Будь-який швидкий зарядний пристрій для " +"телефону або ноутбука підійде.\n" +"\n" +"Чи має значення, яке програмне забезпечення я використовую? Так, для " +"навчання можна використовувати тільки upstream openpilot (і певні його " +"форки)." + +#: system/ui/widgets/network.py:318 system/ui/widgets/network.py:451 +#, python-format +msgid "Forget" +msgstr "Заб-и" + +#: system/ui/widgets/network.py:319 +#, python-format +msgid "Forget Wi-Fi Network \"{}\"?" +msgstr "Забути мережу Wi-Fi \"{}\"?" + +#: selfdrive/ui/layouts/sidebar.py:71 +#: selfdrive/ui/layouts/sidebar.py:125 +msgid "GOOD" +msgstr "ДОБРА" + +#: selfdrive/ui/widgets/pairing_dialog.py:117 +#, python-format +msgid "Go to https://connect.comma.ai on your phone" +msgstr "Перейдіть на сайт https://connect.comma.ai на своєму телефоні." + +#: selfdrive/ui/layouts/sidebar.py:129 +msgid "HIGH" +msgstr "ВИСОКА" + +#: system/ui/widgets/network.py:155 +#, python-format +msgid "Hidden Network" +msgstr "Прихована мережа" + +#: selfdrive/ui/layouts/settings/firehose.py:140 +#, python-format +msgid "INACTIVE: connect to an unmetered network" +msgstr "НЕАКТИВНО: підключення до мережі без ліміту трафіку" + +#: selfdrive/ui/layouts/settings/software.py:53 +#: selfdrive/ui/layouts/settings/software.py:144 +#, python-format +msgid "INSTALL" +msgstr "ВСТАНОВ." + +#: system/ui/widgets/network.py:150 +#, python-format +msgid "IP Address" +msgstr "IP-адреса" + +#: selfdrive/ui/layouts/settings/software.py:53 +#, python-format +msgid "Install Update" +msgstr "Встановити оновлення" + +#: selfdrive/ui/layouts/settings/developer.py:56 +#, python-format +msgid "Joystick Debug Mode" +msgstr "Режим зневадження джойстика" + +#: selfdrive/ui/widgets/ssh_key.py:29 +msgid "LOADING" +msgstr "ЗАВАНТАЖЕННЯ" + +#: selfdrive/ui/layouts/sidebar.py:48 +msgid "LTE" +msgstr "LTE" + +#: selfdrive/ui/layouts/settings/developer.py:64 +#, python-format +msgid "Longitudinal Maneuver Mode" +msgstr "Режим поздовжнього маневрування" + +#: selfdrive/ui/onroad/hud_renderer.py:148 +#, python-format +msgid "MAX" +msgstr "МАКС" + +#: selfdrive/ui/widgets/setup.py:75 +#, python-format +msgid "" +"Maximize your training data uploads to improve openpilot's driving models." +msgstr "" +"Максимізуйте завантаження навчальних даних, щоб поліпшити моделі openpilot." + +#: selfdrive/ui/layouts/settings/device.py:59 +#: selfdrive/ui/layouts/settings/device.py:60 +#, python-format +msgid "N/A" +msgstr "Н/Д" + +#: selfdrive/ui/layouts/sidebar.py:142 +msgid "NO" +msgstr "НЕМАЄ" + +#: selfdrive/ui/layouts/settings/settings.py:60 +msgid "Network" +msgstr "Мережа" + +#: selfdrive/ui/widgets/ssh_key.py:114 +#, python-format +msgid "No SSH keys found" +msgstr "Не знайдено ключів SSH" + +#: selfdrive/ui/widgets/ssh_key.py:126 +#, python-format +msgid "No SSH keys found for user '{}'" +msgstr "Користувач '{}' не має ключів на GitHub" + +#: selfdrive/ui/widgets/offroad_alerts.py:320 +#, python-format +msgid "No release notes available." +msgstr "Інформація про випуск відсутня." + +#: selfdrive/ui/layouts/sidebar.py:73 +#: selfdrive/ui/layouts/sidebar.py:134 +msgid "OFFLINE" +msgstr "ОФЛАЙН" + +#: system/ui/widgets/confirm_dialog.py:93 system/ui/widgets/html_render.py:263 +#: selfdrive/ui/layouts/sidebar.py:127 +#, python-format +msgid "OK" +msgstr "OK" + +#: selfdrive/ui/layouts/sidebar.py:72 +#: selfdrive/ui/layouts/sidebar.py:136 +#: selfdrive/ui/layouts/sidebar.py:144 +msgid "ONLINE" +msgstr "ОНЛАЙН" + +#: selfdrive/ui/widgets/setup.py:20 +#, python-format +msgid "Open" +msgstr "ВІДКРИТИ" + +#: selfdrive/ui/layouts/settings/device.py:48 +#, python-format +msgid "PAIR" +msgstr "ПІДКЛЮЧИТИ" + +#: selfdrive/ui/layouts/sidebar.py:142 +msgid "PANDA" +msgstr "PANDA" + +#: selfdrive/ui/layouts/settings/device.py:62 +#, python-format +msgid "PREVIEW" +msgstr "ПОКАЖИ" + +#: selfdrive/ui/widgets/prime.py:44 +#, python-format +msgid "PRIME FEATURES:" +msgstr "XАРАКТЕРИСТИКИ PRIME:" + +#: selfdrive/ui/layouts/settings/device.py:48 +#, python-format +msgid "Pair Device" +msgstr "Підключити пристрій" + +#: selfdrive/ui/widgets/setup.py:19 +#, python-format +msgid "Pair device" +msgstr "Підключити пристрій" + +#: selfdrive/ui/widgets/pairing_dialog.py:92 +#, python-format +msgid "Pair your device to your comma account" +msgstr "Підключіть свій пристрій до обліковки comma connect" + +#: selfdrive/ui/widgets/setup.py:48 +#: selfdrive/ui/layouts/settings/device.py:24 +#, python-format +msgid "" +"Pair your device with comma connect (connect.comma.ai) and claim your comma " +"prime offer." +msgstr "" +"Підключіть свій пристрій до comma connect (connect.comma.ai) і отримайте " +"свою пропозицію comma prime." + +#: selfdrive/ui/widgets/setup.py:91 +#, python-format +msgid "Please connect to Wi-Fi to complete initial pairing" +msgstr "Будь ласка, підключіться до Wi-Fi, щоб завершити початкове сполучення." + +#: selfdrive/ui/layouts/settings/device.py:55 +#: selfdrive/ui/layouts/settings/device.py:187 +#, python-format +msgid "Power Off" +msgstr "Вимкнути" + +#: system/ui/widgets/network.py:144 +#, python-format +msgid "Prevent large data uploads when on a metered Wi-Fi connection" +msgstr "" +"Запобігайте завантаженню великих обсягів даних під час використання Wi-Fi-" +"з'єднання з обмеженим трафіком" + +#: system/ui/widgets/network.py:135 +#, python-format +msgid "Prevent large data uploads when on a metered cellular connection" +msgstr "" +"Запобігати великим завантаженням даних під час лімітного стільникового " +"з'єднання" + +#: selfdrive/ui/layouts/settings/device.py:25 +msgid "" +"Preview the driver facing camera to ensure that driver monitoring has good " +"visibility. (vehicle must be off)" +msgstr "" +"Попередньо перегляньте камеру, спрямовану на водія, щоб переконатися, що " +"система моніторингу водія має добру видимість. (автомобіль повинен бути " +"вимкнений)" + +#: selfdrive/ui/widgets/pairing_dialog.py:150 +#, python-format +msgid "QR Code Error" +msgstr "Помилка QR-коду" + +#: selfdrive/ui/widgets/ssh_key.py:31 +msgid "REMOVE" +msgstr "ВИДАЛИТИ" + +#: selfdrive/ui/layouts/settings/device.py:51 +#, python-format +msgid "RESET" +msgstr "Скинути" + +#: selfdrive/ui/layouts/settings/device.py:65 +#, python-format +msgid "REVIEW" +msgstr "ДИВИТИСЬ" + +#: selfdrive/ui/layouts/settings/device.py:55 +#: selfdrive/ui/layouts/settings/device.py:175 +#, python-format +msgid "Reboot" +msgstr "Перезавантажити" + +#: selfdrive/ui/onroad/alert_renderer.py:66 +#, python-format +msgid "Reboot Device" +msgstr "Перезавантажте пристрій" + +#: selfdrive/ui/widgets/offroad_alerts.py:112 +#, python-format +msgid "Reboot and Update" +msgstr "Перезавантажити та оновити" + +#: selfdrive/ui/layouts/settings/toggles.py:27 +msgid "" +"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)." +msgstr "" +"Отримувати попередження про необхідність повернутися в смугу, коли ваш " +"автомобіль перетинає виявлену лінію розмітки без увімкненого сигналу " +"повороту під час руху зі швидкістю понад 31 миль/год (50 км/год)." + +#: selfdrive/ui/layouts/settings/toggles.py:76 +#, python-format +msgid "Record and Upload Driver Camera" +msgstr "Писати та вантажити відео з камери водія" + +#: selfdrive/ui/layouts/settings/toggles.py:82 +#, python-format +msgid "Record and Upload Microphone Audio" +msgstr "Запис та завантаження аудіо з мікрофона" + +#: selfdrive/ui/layouts/settings/toggles.py:33 +msgid "" +"Record and store microphone audio while driving. The audio will be included " +"in the dashcam video in comma connect." +msgstr "" +"Записуйте та зберігайте аудіо з мікрофона під час руху. Аудіо буде включено " +"до відео з відеореєстратора в comma connect." + +#: selfdrive/ui/layouts/settings/device.py:67 +#, python-format +msgid "Regulatory" +msgstr "Нормативні документи" + +#: selfdrive/ui/layouts/settings/toggles.py:98 +#, python-format +msgid "Relaxed" +msgstr "Спокійний" + +#: selfdrive/ui/widgets/prime.py:47 +#, python-format +msgid "Remote access" +msgstr "Віддалений доступ" + +#: selfdrive/ui/widgets/prime.py:47 +#, python-format +msgid "Remote snapshots" +msgstr "Віддалені знімки" + +#: selfdrive/ui/widgets/ssh_key.py:123 +#, python-format +msgid "Request timed out" +msgstr "Час запиту вичерпано" + +#: selfdrive/ui/layouts/settings/device.py:119 +#, python-format +msgid "Reset" +msgstr "Скинути" + +#: selfdrive/ui/layouts/settings/device.py:51 +#, python-format +msgid "Reset Calibration" +msgstr "Скинути калібрування" + +#: selfdrive/ui/layouts/settings/device.py:65 +#, python-format +msgid "Review Training Guide" +msgstr "Переглянути посібник з навчання" + +#: selfdrive/ui/layouts/settings/device.py:27 +msgid "Review the rules, features, and limitations of openpilot" +msgstr "Перегляньте правила, функції та обмеження openpilot" + +#: selfdrive/ui/layouts/settings/software.py:61 +#, python-format +msgid "SELECT" +msgstr "ВИБРАТИ" + +#: selfdrive/ui/layouts/settings/developer.py:53 +#, python-format +msgid "SSH Keys" +msgstr "SSH ключі" + +#: system/ui/widgets/network.py:310 +#, python-format +msgid "Scanning Wi-Fi networks..." +msgstr "Пошук мереж..." + +#: system/ui/widgets/option_dialog.py:36 +#, python-format +msgid "Select" +msgstr "Вибрати" + +#: selfdrive/ui/layouts/settings/software.py:191 +#, python-format +msgid "Select a branch" +msgstr "Виберіть гілку" + +#: selfdrive/ui/layouts/settings/device.py:91 +#, python-format +msgid "Select a language" +msgstr "Виберіть мову" + +#: selfdrive/ui/layouts/settings/device.py:60 +#, python-format +msgid "Serial" +msgstr "Серійний номер" + +#: selfdrive/ui/widgets/offroad_alerts.py:106 +#, python-format +msgid "Snooze Update" +msgstr "Відкласти оновлення" + +#: selfdrive/ui/layouts/settings/settings.py:62 +msgid "Software" +msgstr "Програма" + +#: selfdrive/ui/layouts/settings/toggles.py:98 +#, python-format +msgid "Standard" +msgstr "Стандарт" + +#: selfdrive/ui/layouts/settings/toggles.py:22 +msgid "" +"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 your steering wheel distance button." +msgstr "" +"Рекомендується стандартний режим. В агресивному режимі openpilot буде " +"триматися ближче до автомобілів попереду і більш агресивно використовувати " +"газ і гальма. У спокійному режимі openpilot буде триматися на більшій " +"відстані від автомобілів попереду. На підтримуваних автомобілях ви можете " +"перемикатися між цими режимами за допомогою кнопки дистанції на кермі." + +#: selfdrive/ui/onroad/alert_renderer.py:59 +#: selfdrive/ui/onroad/alert_renderer.py:65 +#, python-format +msgid "System Unresponsive" +msgstr "Система не реагує" + +#: selfdrive/ui/onroad/alert_renderer.py:58 +#, python-format +msgid "TAKE CONTROL IMMEDIATELY" +msgstr "КЕРМУЙТЕ НЕГАЙНО" + +#: selfdrive/ui/layouts/sidebar.py:71 +#: selfdrive/ui/layouts/sidebar.py:125 +#: selfdrive/ui/layouts/sidebar.py:127 +#: selfdrive/ui/layouts/sidebar.py:129 +msgid "TEMP" +msgstr "ТЕМП" + +#: selfdrive/ui/layouts/settings/software.py:61 +#, python-format +msgid "Target Branch" +msgstr "Цільова гілка" + +#: system/ui/widgets/network.py:124 +#, python-format +msgid "Tethering Password" +msgstr "Пароль для точки доступу" + +#: selfdrive/ui/layouts/settings/settings.py:61 +msgid "Toggles" +msgstr "Перемикачі" + +#: selfdrive/ui/layouts/settings/software.py:72 +#, python-format +msgid "UNINSTALL" +msgstr "ВИДАЛИТИ" + +#: selfdrive/ui/layouts/home.py:155 +#, python-format +msgid "UPDATE" +msgstr "ОНОВИТИ" + +#: selfdrive/ui/layouts/settings/software.py:72 +#: selfdrive/ui/layouts/settings/software.py:171 +#, python-format +msgid "Uninstall" +msgstr "Видалити" + +#: selfdrive/ui/layouts/sidebar.py:117 +msgid "Unknown" +msgstr "Невідомо" + +#: selfdrive/ui/layouts/settings/software.py:48 +#, python-format +msgid "Updates are only downloaded while the car is off." +msgstr "Оновлення завантажуються лише тоді, коли автомобіль вимкнено." + +#: selfdrive/ui/widgets/prime.py:33 +#, python-format +msgid "Upgrade Now" +msgstr "Оновити зараз" + +#: selfdrive/ui/layouts/settings/toggles.py:31 +msgid "" +"Upload data from the driver facing camera and help improve the driver " +"monitoring algorithm." +msgstr "" +"Завантажуйте дані з камери, спрямованої на водія, та допоможіть покращити " +"алгоритм моніторингу водія." + +#: selfdrive/ui/layouts/settings/toggles.py:88 +#, python-format +msgid "Use Metric System" +msgstr "Використовувати метричну систему" + +#: selfdrive/ui/layouts/settings/toggles.py:17 +msgid "" +"Use the openpilot system for adaptive cruise control and lane keep driver " +"assistance. Your attention is required at all times to use this feature." +msgstr "" +"Використовуйте систему openpilot для адаптивного круїз-контролю та допомоги " +"в утриманні смуги руху. Ваша увага потрібна постійно при використанні цієї " +"функції. Зміна цього налаштування набуває чинності після вимкнення живлення " +"автомобіля." + +#: selfdrive/ui/layouts/sidebar.py:72 +#: selfdrive/ui/layouts/sidebar.py:144 +msgid "VEHICLE" +msgstr "АВТО" + +#: selfdrive/ui/layouts/settings/device.py:67 +#, python-format +msgid "VIEW" +msgstr "ДИВИСЬ" + +#: selfdrive/ui/onroad/alert_renderer.py:52 +#, python-format +msgid "Waiting to start" +msgstr "Очікування початку" + +#: selfdrive/ui/layouts/settings/developer.py:19 +msgid "" +"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." +msgstr "" +"Попередження: це надає доступ по SSH до всіх публічних ключів у ваших " +"налаштуваннях GitHub. Ніколи не вводьте ім'я користувача GitHub, окрім " +"вашого власного. Співробітник comma НІКОЛИ не попросить вас додати його ім'я " +"користувача GitHub." + +#: selfdrive/ui/layouts/onboarding.py:111 +#, python-format +msgid "Welcome to openpilot" +msgstr "Ласкаво просимо до openpilot" + +#: selfdrive/ui/layouts/settings/toggles.py:20 +msgid "When enabled, pressing the accelerator pedal will disengage openpilot." +msgstr "Якщо увімкнено, натискання на педаль акселератора вимкне openpilot." + +#: selfdrive/ui/layouts/sidebar.py:44 +msgid "Wi-Fi" +msgstr "Wi-Fi" + +#: system/ui/widgets/network.py:144 +#, python-format +msgid "Wi-Fi Network Metered" +msgstr "Трафік Wi-Fi" + +#: system/ui/widgets/network.py:314 +#, python-format +msgid "Wrong password" +msgstr "Невірний пароль" + +#: selfdrive/ui/layouts/onboarding.py:145 +#, python-format +msgid "You must accept the Terms and Conditions in order to use openpilot." +msgstr "Ви повинні прийняти Умови та положення, щоб користуватися openpilot." + +#: selfdrive/ui/layouts/onboarding.py:112 +#, python-format +msgid "" +"You must accept the Terms and Conditions to use openpilot. Read the latest " +"terms at https://comma.ai/terms before continuing." +msgstr "" +"Ви повинні прийняти Умови використання, щоб користуватися openpilot. Перед " +"тим, як продовжити, ознайомтеся з останніми умовами на сайті https://" +"comma.ai/terms." + +#: selfdrive/ui/onroad/driver_camera_dialog.py:34 +#, python-format +msgid "camera starting" +msgstr "запуск камери" + +#: selfdrive/ui/layouts/settings/software.py:105 +#, python-format +msgid "checking..." +msgstr "перевіряю..." + +#: selfdrive/ui/widgets/prime.py:63 +#, python-format +msgid "comma prime" +msgstr "comma prime" + +#: system/ui/widgets/network.py:142 +#, python-format +msgid "default" +msgstr "замовч." + +#: selfdrive/ui/layouts/settings/device.py:133 +#, python-format +msgid "down" +msgstr "вниз" + +#: selfdrive/ui/layouts/settings/software.py:106 +#, python-format +msgid "downloading..." +msgstr "завантажую..." + +#: selfdrive/ui/layouts/settings/software.py:114 +#, python-format +msgid "failed to check for update" +msgstr "не вдалося перевірити оновлення" + +#: selfdrive/ui/layouts/settings/software.py:107 +#, python-format +msgid "finalizing update..." +msgstr "завершую..." + +#: system/ui/widgets/network.py:237 system/ui/widgets/network.py:314 +#, python-format +msgid "for \"{}\"" +msgstr "для \"{}\"" + +#: selfdrive/ui/onroad/hud_renderer.py:177 +#, python-format +msgid "km/h" +msgstr "км/год" + +#: system/ui/widgets/network.py:204 +#, python-format +msgid "leave blank for automatic configuration" +msgstr "залиште порожнім для автоматичного налаштування" + +#: selfdrive/ui/layouts/settings/device.py:134 +#, python-format +msgid "left" +msgstr "вліво" + +#: system/ui/widgets/network.py:142 +#, python-format +msgid "metered" +msgstr "обмеж." + +#: selfdrive/ui/onroad/hud_renderer.py:177 +#, python-format +msgid "mph" +msgstr "миль/год" + +#: selfdrive/ui/layouts/settings/software.py:20 +#, python-format +msgid "never" +msgstr "ніколи" + +#: selfdrive/ui/layouts/settings/software.py:31 +#, python-format +msgid "now" +msgstr "зараз" + +#: selfdrive/ui/layouts/settings/developer.py:71 +#, python-format +msgid "openpilot Longitudinal Control (Alpha)" +msgstr "Поздовжнє керування openpilot (Альфа)" + +#: selfdrive/ui/onroad/alert_renderer.py:51 +#, python-format +msgid "openpilot Unavailable" +msgstr "openpilot Недоступний" + +#: selfdrive/ui/layouts/settings/toggles.py:158 +#, python-format +msgid "" +"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:

End-to-End Longitudinal Control


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." +"

New Driving Visualization


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." +msgstr "" +"openpilot за замовчуванням працює в режимі спокій. Експериментальний режим " +"увімкне функції альфа-рівня, які ще не готові для режиму спокій. " +"Експериментальні функції перелічені нижче:

Кінцевий поздовжній " +"контроль


Дозвольте моделі водіння контролювати газ і гальма. " +"openpilot буде керувати автомобілем так, як це робив би людина, включаючи " +"зупинку на червоне світло і знаки зупинки. Оскільки модель водіння визначає " +"швидкість руху, задана швидкість буде діяти лише як верхня межа. Це функція " +"альфа-рівня; слід очікувати помилок.

Нова візуалізація водіння
Візуалізація водіння перейде на ширококутну камеру, спрямовану на " +"дорогу, при низьких швидкостях, щоб краще показувати деякі повороти. Логотип " +"експериментального режиму також буде показаний у верхньому правому куті." + +#: selfdrive/ui/layouts/settings/device.py:165 +#, python-format +msgid "" +"openpilot is continuously calibrating, resetting is rarely required. " +"Resetting calibration will restart openpilot if the car is powered on." +msgstr "" +"openpilot постійно калібрується, скидання рідко потрібне. Скидання " +"калібрування призведе до перезапуску openpilot, якщо автомобіль увімкнено." + +#: selfdrive/ui/layouts/settings/firehose.py:20 +msgid "" +"openpilot learns to drive by watching humans, like you, drive.\n" +"\n" +"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." +msgstr "" +"openpilot вчиться керувати автомобілем, спостерігаючи за тим, як це роблять " +"люди, такі як ви.\n" +"\n" +"Режим зливи дозволяє максимально збільшити обсяг завантажуваних навчальних " +"даних, щоб поліпшити моделі керування автомобілем openpilot. Більше даних " +"означає більші моделі, а це означає кращий експериментальний режим." + +#: selfdrive/ui/layouts/settings/toggles.py:183 +#, python-format +msgid "openpilot longitudinal control may come in a future update." +msgstr "Поздовжнє керування openpilot може з'явитися в майбутньому оновленні." + +#: selfdrive/ui/layouts/settings/device.py:26 +msgid "" +"openpilot requires the device to be mounted within 4° left or right and " +"within 5° up or 9° down." +msgstr "" +"Для роботи openpilot потрібно, щоб пристрій був встановлений з нахилом не " +"більше 4° вліво або вправо та не більше 5° вгору або 9° вниз. openpilot " +"постійно калібрується, тому скидання калібрування потрібне рідко." + +#: selfdrive/ui/layouts/settings/device.py:134 +#, python-format +msgid "right" +msgstr "вправо" + +#: system/ui/widgets/network.py:142 +#, python-format +msgid "unmetered" +msgstr "необмеж." + +#: selfdrive/ui/layouts/settings/device.py:133 +#, python-format +msgid "up" +msgstr "вгору" + +#: selfdrive/ui/layouts/settings/software.py:125 +#, python-format +msgid "up to date, last checked never" +msgstr "оновлено, ніколи не перевірялось" + +#: selfdrive/ui/layouts/settings/software.py:123 +#, python-format +msgid "up to date, last checked {}" +msgstr "оновлено, перевірив {}" + +#: selfdrive/ui/layouts/settings/software.py:117 +#, python-format +msgid "update available" +msgstr "доступне оновлення" + +#: selfdrive/ui/layouts/home.py:169 +#, python-format +msgid "{} ALERT" +msgid_plural "{} ALERTS" +msgstr[0] "{} СПОВІЩЕННЯ" +msgstr[1] "{} СПОВІЩЕННЯ" +msgstr[2] "{} СПОВІЩЕНЬ" + +#: selfdrive/ui/layouts/settings/software.py:40 +#, python-format +msgid "{} day ago" +msgid_plural "{} days ago" +msgstr[0] "{} день тому" +msgstr[1] "{} дні тому" +msgstr[2] "{} днів тому" + +#: selfdrive/ui/layouts/settings/software.py:37 +#, python-format +msgid "{} hour ago" +msgid_plural "{} hours ago" +msgstr[0] "{} година тому" +msgstr[1] "{} години тому" +msgstr[2] "{} годин тому" + +#: selfdrive/ui/layouts/settings/software.py:34 +#, python-format +msgid "{} minute ago" +msgid_plural "{} minutes ago" +msgstr[0] "{} хвилина тому" +msgstr[1] "{} хвилини тому" +msgstr[2] "{} хвилин тому" + +#: selfdrive/ui/layouts/settings/firehose.py:111 +#, python-format +msgid "{} segment of your driving is in the training dataset so far." +msgid_plural "{} segments of your driving is in the training dataset so far." +msgstr[0] "" +"{} сегмент вашого водіння на даний момент містяться в тренувальному наборі " +"даних." +msgstr[1] "" +"{} сегменти вашого водіння на даний момент містяться в тренувальному наборі " +"даних." +msgstr[2] "" +"{} сегментів вашого водіння на даний момент містяться в тренувальному наборі " +"даних." + +#: selfdrive/ui/widgets/prime.py:62 +#, python-format +msgid "✓ SUBSCRIBED" +msgstr "✓ ПІДПИСАНО" + +#: selfdrive/ui/widgets/setup.py:22 +#, python-format +msgid "🔥 Firehose Mode 🔥" +msgstr "🌧️ Режим зливи 🌧️" diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index b0674dee82..47e673ce89 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -5,6 +5,7 @@ "Português": "pt-BR", "Español": "es", "Türkçe": "tr", + "Українська": "uk", "العربية": "ar", "ไทย": "th", "中文(繁體)": "zh-CHT", diff --git a/sunnypilot/models/tests/model_hash b/sunnypilot/models/tests/model_hash index 82ff797b5b..f37b9dba50 100644 --- a/sunnypilot/models/tests/model_hash +++ b/sunnypilot/models/tests/model_hash @@ -1 +1 @@ -030a2a502e95e51290bb1d76795013b72b25521a572c3942a232b9395e544250 \ No newline at end of file +6168bc755ea17aececa535e8b94e6c798e5e855bfc47be19220d5cbc08483332 \ No newline at end of file diff --git a/sunnypilot/selfdrive/controls/lib/latcontrol_torque_ext_base.py b/sunnypilot/selfdrive/controls/lib/latcontrol_torque_ext_base.py index 31c2182d41..c6658bdc78 100644 --- a/sunnypilot/selfdrive/controls/lib/latcontrol_torque_ext_base.py +++ b/sunnypilot/selfdrive/controls/lib/latcontrol_torque_ext_base.py @@ -15,9 +15,8 @@ LAT_PLAN_MIN_IDX = 5 LATERAL_LAG_MOD = 0.0 # seconds, modifies how far in the future we look ahead for the lateral plan # from selfdrive/controls/lib/latcontrol_torque.py -KP = 1.0 -KI = 0.3 -KD = 0.0 +KP = 0.8 +KI = 0.15 INTERP_SPEEDS = [1, 1.5, 2.0, 3.0, 5, 7.5, 10, 15, 30] KP_INTERP = [250, 120, 65, 30, 11.5, 5.5, 3.5, 2.0, KP] @@ -64,7 +63,7 @@ class LatControlTorqueExtBase: self.torque_from_lateral_accel_in_torque_space = CI.torque_from_lateral_accel_in_torque_space() self._ff = 0.0 - self._pid = PIDController([INTERP_SPEEDS, KP_INTERP], KI, KD) + self._pid = PIDController([INTERP_SPEEDS, KP_INTERP], KI) self._pid_log = None self._setpoint = 0.0 self._measurement = 0.0 diff --git a/sunnypilot/sunnylink/api.py b/sunnypilot/sunnylink/api.py index 26c3f3462d..3c78dd3e55 100644 --- a/sunnypilot/sunnylink/api.py +++ b/sunnypilot/sunnylink/api.py @@ -2,9 +2,10 @@ import json import os import random import time -from datetime import datetime, timedelta - import jwt +from typing import cast +from datetime import datetime, timedelta, UTC + from openpilot.common.api.base import BaseApi from openpilot.common.params import Params from openpilot.system.hardware import HARDWARE @@ -92,7 +93,8 @@ class SunnylinkApi(BaseApi): backoff = 1 while True: - register_token = jwt.encode({'register': True, 'exp': datetime.utcnow() + timedelta(hours=1)}, private_key, algorithm=jwt_algo) + register_token = jwt.encode({'register': True, 'exp': datetime.now(UTC).replace(tzinfo=None) + timedelta(hours=1)}, + cast(str, private_key), algorithm=jwt_algo) try: if verbose or time.monotonic() - start_time < timeout / 2: self._status_update("Registering device to sunnylink...") diff --git a/sunnypilot/sunnylink/params_metadata.json b/sunnypilot/sunnylink/params_metadata.json index 4cc6b18089..3228fd0d62 100644 --- a/sunnypilot/sunnylink/params_metadata.json +++ b/sunnypilot/sunnylink/params_metadata.json @@ -458,6 +458,10 @@ "title": "Language", "description": "" }, + "LastAgnosPowerMonitorShutdown": { + "title": "Last AGNOS Power Monitor Shutdown", + "description": "" + }, "LastAthenaPingTime": { "title": "Last Athena Ping Time", "description": "" diff --git a/sunnypilot/sunnylink/statsd.py b/sunnypilot/sunnylink/statsd.py index 70d3d58e94..233b531e85 100755 --- a/sunnypilot/sunnylink/statsd.py +++ b/sunnypilot/sunnylink/statsd.py @@ -17,7 +17,7 @@ from cereal.messaging import SubMaster from openpilot.system.hardware.hw import Paths from openpilot.common.swaglog import cloudlog from openpilot.system.hardware import HARDWARE -from openpilot.common.utils import atomic_write_in_dir +from openpilot.common.utils import atomic_write from openpilot.system.version import get_build_metadata from openpilot.system.loggerd.config import STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S from openpilot.system.statsd import METRIC_TYPE, StatLogSP @@ -242,7 +242,7 @@ def stats_main(end_event): if len(os.listdir(STATS_DIR)) < STATS_DIR_FILE_LIMIT: if len(result) > 0: stats_path = os.path.join(STATS_DIR, f"{boot_uid}_{idx}") - with atomic_write_in_dir(stats_path) as f: + with atomic_write(stats_path) as f: f.write(result) idx += 1 else: diff --git a/system/athena/athenad.py b/system/athena/athenad.py index 22e15051da..1f4187e8f7 100755 --- a/system/athena/athenad.py +++ b/system/athena/athenad.py @@ -31,7 +31,7 @@ from websocket import (ABNF, WebSocket, WebSocketException, WebSocketTimeoutExce import cereal.messaging as messaging from cereal import log from cereal.services import SERVICE_LIST -from openpilot.common.api import Api +from openpilot.common.api import Api, get_key_pair from openpilot.common.utils import CallbackReader, get_upload_stream from openpilot.common.params import Params from openpilot.common.realtime import set_core_affinity @@ -554,11 +554,8 @@ def start_local_proxy_shim(global_end_event: threading.Event, local_port: int, w @dispatcher.add_method def getPublicKey() -> str | None: - if not os.path.isfile(Paths.persist_root() + '/comma/id_rsa.pub'): - return None - - with open(Paths.persist_root() + '/comma/id_rsa.pub') as f: - return f.read() + _, _, public_key = get_key_pair() + return public_key @dispatcher.add_method diff --git a/system/athena/registration.py b/system/athena/registration.py index c6da463bd2..26a2adb1af 100755 --- a/system/athena/registration.py +++ b/system/athena/registration.py @@ -2,6 +2,7 @@ import time import json import jwt +from typing import cast from pathlib import Path from datetime import datetime, timedelta, UTC @@ -69,7 +70,9 @@ def register(show_spinner=False) -> str | None: start_time = time.monotonic() while True: try: - register_token = jwt.encode({'register': True, 'exp': datetime.now(UTC).replace(tzinfo=None) + timedelta(hours=1)}, private_key, algorithm=jwt_algo) + register_token = jwt.encode({'register': True, 'exp': datetime.now(UTC).replace(tzinfo=None) + timedelta(hours=1)}, + cast(str, private_key), algorithm=jwt_algo) + cloudlog.info("getting pilotauth") cloudlog.info("getting pilotauth") resp = api_get("v2/pilotauth/", method='POST', timeout=15, imei=imei1, imei2=imei2, serial=serial, public_key=public_key, register_token=register_token) diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index caf7871573..0d93b70465 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -1004,8 +1004,8 @@ bool SpectraCamera::openSensor() { }; // Figure out which sensor we have - if (!init_sensor_lambda(new OX03C10) && - !init_sensor_lambda(new OS04C10)) { + if (!init_sensor_lambda(new OS04C10) && + !init_sensor_lambda(new OX03C10)) { LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); enabled = false; return false; diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc index 38be4ecca4..62c26ca809 100644 --- a/system/camerad/sensors/os04c10.cc +++ b/system/camerad/sensors/os04c10.cc @@ -1,6 +1,7 @@ #include #include "system/camerad/sensors/sensor.h" +#include "third_party/linux/include/msm_camsensor_sdk.h" namespace { @@ -51,7 +52,7 @@ OS04C10::OS04C10() { probe_expected_data = 0x5304; bits_per_pixel = 12; mipi_format = CAM_FORMAT_MIPI_RAW_12; - frame_data_type = 0x2c; + frame_data_type = CSI_RAW12; mclk_frequency = 24000000; // Hz // TODO: this was set from logs. actually calculate it out diff --git a/system/camerad/sensors/os04c10_registers.h b/system/camerad/sensors/os04c10_registers.h index 7cd9e97be5..28d6b3310c 100644 --- a/system/camerad/sensors/os04c10_registers.h +++ b/system/camerad/sensors/os04c10_registers.h @@ -4,10 +4,10 @@ const struct i2c_random_wr_payload start_reg_array_os04c10[] = {{0x100, 1}}; const struct i2c_random_wr_payload stop_reg_array_os04c10[] = {{0x100, 0}}; const struct i2c_random_wr_payload init_array_os04c10[] = { - // DP_2688X1520_NEWSTG_MIPI0776Mbps_30FPS_10BIT_FOURLANE - {0x0103, 0x01}, + // baseed on DP_2688X1520_NEWSTG_MIPI0776Mbps_30FPS_10BIT_FOURLANE + {0x0103, 0x01}, // software reset - // PLL + // PLL + clocks {0x0301, 0xe4}, {0x0303, 0x01}, {0x0305, 0xb6}, @@ -24,7 +24,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x3106, 0x21}, {0x3107, 0xa1}, - // ? + // Analog/timing fine-tuning block {0x3624, 0x00}, {0x3625, 0x4c}, {0x3660, 0x04}, @@ -101,7 +101,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x3f00, 0x0b}, {0x3f06, 0x04}, - // BLC + // BLC - black level correction {0x400a, 0x01}, {0x400b, 0x50}, {0x400e, 0x08}, @@ -157,7 +157,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x5180, 0x70}, {0x5181, 0x10}, - // DPC + // DPC - defective pixel correction {0x520a, 0x03}, {0x520b, 0x06}, {0x520c, 0x0c}, @@ -248,7 +248,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x4008, 0x01}, {0x4009, 0x06}, - // FSIN + // FSIN - frame sync {0x3002, 0x22}, {0x3663, 0x22}, {0x368a, 0x04}, @@ -276,8 +276,8 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x3816, 0x03}, {0x3817, 0x01}, - {0x380c, 0x0b}, {0x380d, 0xac}, // HTS - {0x380e, 0x06}, {0x380f, 0x9c}, // VTS + {0x380c, 0x0b}, {0x380d, 0xac}, // HTS (line length) + {0x380e, 0x06}, {0x380f, 0x9c}, // VTS (frame length) {0x3820, 0xb3}, {0x3821, 0x01}, @@ -309,17 +309,17 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { // initialize exposure {0x3503, 0x88}, - // long + // long exposure {0x3500, 0x00}, {0x3501, 0x00}, {0x3502, 0x10}, {0x3508, 0x00}, {0x3509, 0x80}, {0x350a, 0x04}, {0x350b, 0x00}, - // short + // short exposure {0x3510, 0x00}, {0x3511, 0x00}, {0x3512, 0x40}, {0x350c, 0x00}, {0x350d, 0x80}, {0x350e, 0x04}, {0x350f, 0x00}, - // wb + // white balance // b {0x5100, 0x06}, {0x5101, 0x7e}, {0x5140, 0x06}, {0x5141, 0x7e}, @@ -332,7 +332,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { }; const struct i2c_random_wr_payload ife_downscale_override_array_os04c10[] = { - // OS04C10_AA_00_02_17_wAO_2688x1524_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz + // based on OS04C10_AA_00_02_17_wAO_2688x1524_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz {0x3c8c, 0x40}, {0x3714, 0x24}, {0x37c2, 0x04}, diff --git a/system/camerad/sensors/ox03c10.cc b/system/camerad/sensors/ox03c10.cc index 6f7e658f48..05d58f03c6 100644 --- a/system/camerad/sensors/ox03c10.cc +++ b/system/camerad/sensors/ox03c10.cc @@ -1,6 +1,7 @@ #include #include "system/camerad/sensors/sensor.h" +#include "third_party/linux/include/msm_camsensor_sdk.h" namespace { @@ -40,8 +41,8 @@ OX03C10::OX03C10() { probe_expected_data = 0x5803; bits_per_pixel = 12; mipi_format = CAM_FORMAT_MIPI_RAW_12; - frame_data_type = 0x2c; // one is 0x2a, two are 0x2b - mclk_frequency = 24000000; //Hz + frame_data_type = CSI_RAW12; + mclk_frequency = 24000000; // Hz readout_time_ns = 14697000; diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h index 8a0c066942..d59b45efcb 100644 --- a/system/hardware/tici/hardware.h +++ b/system/hardware/tici/hardware.h @@ -7,7 +7,6 @@ #include #include // for std::clamp -#include "common/params.h" #include "common/util.h" #include "system/hardware/base.h" diff --git a/system/loggerd/tests/test_loggerd.py b/system/loggerd/tests/test_loggerd.py index c6a4b12e63..1cac16adcd 100644 --- a/system/loggerd/tests/test_loggerd.py +++ b/system/loggerd/tests/test_loggerd.py @@ -16,6 +16,7 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.common.timeout import Timeout from openpilot.system.hardware.hw import Paths +from openpilot.system.hardware import TICI from openpilot.system.loggerd.xattr_cache import getxattr from openpilot.system.loggerd.deleter import PRESERVE_ATTR_NAME, PRESERVE_ATTR_VALUE from openpilot.system.manager.process_config import managed_processes @@ -221,13 +222,16 @@ class TestLoggerd: assert abs(boot.wallTimeNanos - time.time_ns()) < 5*1e9 # within 5s assert boot.launchLog == launch_log - for fn in ["console-ramoops", "pmsg-ramoops-0"]: - path = Path(os.path.join("/sys/fs/pstore/", fn)) - if path.is_file(): - with open(path, "rb") as f: - expected_val = f.read() - bootlog_val = [e.value for e in boot.pstore.entries if e.key == fn][0] - assert expected_val == bootlog_val + if TICI: + for fn in ["console-ramoops", "pmsg-ramoops-0"]: + path = Path(os.path.join("/sys/fs/pstore/", fn)) + if path.is_file(): + with open(path, "rb") as f: + expected_val = f.read() + bootlog_val = [e.value for e in boot.pstore.entries if e.key == fn][0] + assert expected_val == bootlog_val + else: + assert len(boot.pstore.entries) == 0 # next one should increment by one bl1 = re.match(RE.LOG_ID_V2, bootlog_path.name) diff --git a/system/manager/build.py b/system/manager/build.py index c88befd454..d79e7fd2ad 100755 --- a/system/manager/build.py +++ b/system/manager/build.py @@ -14,7 +14,7 @@ from openpilot.system.version import get_build_metadata MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") -TOTAL_SCONS_NODES = 2280 +TOTAL_SCONS_NODES = 2705 MAX_BUILD_PROGRESS = 100 def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: diff --git a/system/manager/manager.py b/system/manager/manager.py index d70b4d74b7..36e45488f6 100755 --- a/system/manager/manager.py +++ b/system/manager/manager.py @@ -9,6 +9,7 @@ import traceback from cereal import log import cereal.messaging as messaging import openpilot.system.sentry as sentry +from openpilot.common.utils import atomic_write from openpilot.common.params import Params, ParamKeyFlag from openpilot.common.text_window import TextWindow from openpilot.system.hardware import HARDWARE @@ -168,7 +169,7 @@ def manager_thread() -> None: # kick AGNOS power monitoring watchdog try: if sm.all_checks(['deviceState']): - with open("/var/tmp/power_watchdog", "w") as f: + with atomic_write("/var/tmp/power_watchdog", "w", overwrite=True) as f: f.write(str(time.monotonic())) except Exception: pass diff --git a/system/manager/process.py b/system/manager/process.py index e6b6a44c40..1e24198267 100644 --- a/system/manager/process.py +++ b/system/manager/process.py @@ -67,6 +67,7 @@ class ManagerProcess(ABC): enabled = True name = "" shutting_down = False + restart_if_crash = False @abstractmethod def prepare(self) -> None: @@ -167,13 +168,14 @@ class NativeProcess(ManagerProcess): class PythonProcess(ManagerProcess): - def __init__(self, name, module, should_run, enabled=True, sigkill=False): + def __init__(self, name, module, should_run, enabled=True, sigkill=False, restart_if_crash=False): self.name = name self.module = module self.should_run = should_run self.enabled = enabled self.sigkill = sigkill self.launcher = launcher + self.restart_if_crash = restart_if_crash def prepare(self) -> None: if self.enabled: @@ -252,6 +254,9 @@ def ensure_running(procs: ValuesView[ManagerProcess], started: bool, params=None running = [] for p in procs: if p.enabled and p.name not in not_run and p.should_run(started, params, CP): + if p.restart_if_crash and p.proc is not None and not p.proc.is_alive(): + cloudlog.error(f'Restarting {p.name} (exitcode {p.proc.exitcode})') + p.restart() running.append(p) else: p.stop(block=False) diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 23c7a0116c..793fbc07fa 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -126,7 +126,7 @@ procs = [ PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(WEBCAM or not PC)), PythonProcess("sensord", "system.sensord.sensord", only_onroad, enabled=not PC), - PythonProcess("ui", "selfdrive.ui.ui", always_run), + PythonProcess("ui", "selfdrive.ui.ui", always_run, restart_if_crash=True), PythonProcess("soundd", "selfdrive.ui.soundd", driverview), PythonProcess("locationd", "selfdrive.locationd.locationd", only_onroad), NativeProcess("_pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), diff --git a/system/statsd.py b/system/statsd.py index 17a5e4190e..3a67dd44c2 100755 --- a/system/statsd.py +++ b/system/statsd.py @@ -17,7 +17,7 @@ from cereal.messaging import SubMaster from openpilot.system.hardware.hw import Paths from openpilot.common.swaglog import cloudlog from openpilot.system.hardware import HARDWARE -from openpilot.common.utils import atomic_write_in_dir +from openpilot.common.utils import atomic_write from openpilot.system.version import get_build_metadata from openpilot.system.loggerd.config import STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S @@ -218,7 +218,7 @@ def main() -> NoReturn: if len(os.listdir(STATS_DIR)) < STATS_DIR_FILE_LIMIT: if len(result) > 0: stats_path = os.path.join(STATS_DIR, f"{boot_uid}_{idx}") - with atomic_write_in_dir(stats_path) as f: + with atomic_write(stats_path) as f: f.write(result) idx += 1 else: diff --git a/system/ui/README.md b/system/ui/README.md index 796d298626..54697dada8 100644 --- a/system/ui/README.md +++ b/system/ui/README.md @@ -10,6 +10,7 @@ Quick start: * set `BURN_IN=1` to get a burn-in heatmap version of the UI * set `GRID=50` to show a 50-pixel alignment grid overlay * set `MAGIC_DEBUG=1` to show every dropped frames (only on device) +* set `RECORD=1` to record the screen, output defaults to `output.mp4` but can be set with `RECORD_OUTPUT` * set `SUNNYPILOT_UI=0` to run the stock UI instead of the sunnypilot UI * https://www.raylib.com/cheatsheet/cheatsheet.html * https://electronstudio.github.io/raylib-python-cffi/README.html#quickstart diff --git a/system/ui/lib/application.py b/system/ui/lib/application.py index 60a110293d..20f2d3a424 100644 --- a/system/ui/lib/application.py +++ b/system/ui/lib/application.py @@ -7,11 +7,13 @@ import sys import pyray as rl import threading import platform +import subprocess from contextlib import contextmanager from collections.abc import Callable from collections import deque from dataclasses import dataclass from enum import StrEnum +from pathlib import Path from typing import NamedTuple from importlib.resources import as_file, files from openpilot.common.swaglog import cloudlog @@ -38,6 +40,8 @@ SCALE = float(os.getenv("SCALE", "1.0")) GRID_SIZE = int(os.getenv("GRID", "0")) PROFILE_RENDER = int(os.getenv("PROFILE_RENDER", "0")) PROFILE_STATS = int(os.getenv("PROFILE_STATS", "100")) # Number of functions to show in profile output +RECORD = os.getenv("RECORD") == "1" +RECORD_OUTPUT = str(Path(os.getenv("RECORD_OUTPUT", "output")).with_suffix(".mp4")) GL_VERSION = """ #version 300 es @@ -200,10 +204,15 @@ class GuiApplication(GuiApplicationExt): else: self._scale = SCALE + # Scale, then ensure dimensions are even self._scaled_width = int(self._width * self._scale) self._scaled_height = int(self._height * self._scale) + self._scaled_width += self._scaled_width % 2 + self._scaled_height += self._scaled_height % 2 + self._render_texture: rl.RenderTexture | None = None self._burn_in_shader: rl.Shader | None = None + self._ffmpeg_proc: subprocess.Popen | None = None self._textures: dict[str, rl.Texture] = {} self._target_fps: int = _DEFAULT_FPS self._last_fps_log_time: float = time.monotonic() @@ -264,12 +273,33 @@ class GuiApplication(GuiApplicationExt): rl.set_config_flags(flags) rl.init_window(self._scaled_width, self._scaled_height, title) - needs_render_texture = self._scale != 1.0 or BURN_IN_MODE + + needs_render_texture = self._scale != 1.0 or BURN_IN_MODE or RECORD if self._scale != 1.0: rl.set_mouse_scale(1 / self._scale, 1 / self._scale) if needs_render_texture: self._render_texture = rl.load_render_texture(self._width, self._height) rl.set_texture_filter(self._render_texture.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) + + if RECORD: + ffmpeg_args = [ + 'ffmpeg', + '-v', 'warning', # Reduce ffmpeg log spam + '-stats', # Show encoding progress + '-f', 'rawvideo', # Input format + '-pix_fmt', 'rgba', # Input pixel format + '-s', f'{self._width}x{self._height}', # Input resolution + '-r', str(fps), # Input frame rate + '-i', 'pipe:0', # Input from stdin + '-vf', 'vflip,format=yuv420p', # Flip vertically and convert rgba to yuv420p + '-c:v', 'libx264', # Video codec + '-preset', 'ultrafast', # Encoding speed + '-y', # Overwrite existing file + '-f', 'mp4', # Output format + RECORD_OUTPUT, # Output file path + ] + self._ffmpeg_proc = subprocess.Popen(ffmpeg_args, stdin=subprocess.PIPE) + rl.set_target_fps(fps) self._target_fps = fps @@ -314,6 +344,9 @@ class GuiApplication(GuiApplicationExt): def set_modal_overlay(self, overlay, callback: Callable | None = None): if self._modal_overlay.overlay is not None: + if hasattr(self._modal_overlay.overlay, 'hide_event'): + self._modal_overlay.overlay.hide_event() + if self._modal_overlay.callback is not None: self._modal_overlay.callback(-1) @@ -377,6 +410,16 @@ class GuiApplication(GuiApplicationExt): rl.unload_image(image) return texture + def close_ffmpeg(self): + if self._ffmpeg_proc is not None: + self._ffmpeg_proc.stdin.flush() + self._ffmpeg_proc.stdin.close() + try: + self._ffmpeg_proc.wait(timeout=5) + except subprocess.TimeoutExpired: + self._ffmpeg_proc.terminate() + self._ffmpeg_proc.wait() + def close(self): if not rl.is_window_ready(): return @@ -400,6 +443,8 @@ class GuiApplication(GuiApplicationExt): if not PC: self._mouse.stop() + self.close_ffmpeg() + rl.close_window() @property @@ -477,6 +522,15 @@ class GuiApplication(GuiApplicationExt): self._draw_grid() rl.end_drawing() + + if RECORD: + image = rl.load_image_from_texture(self._render_texture.texture) + data_size = image.width * image.height * 4 + data = bytes(rl.ffi.buffer(image.data, data_size)) + self._ffmpeg_proc.stdin.write(data) + self._ffmpeg_proc.stdin.flush() + rl.unload_image(image) + self._monitor_fps() self._frame += 1 @@ -514,6 +568,8 @@ class GuiApplication(GuiApplicationExt): # Clear the overlay and execute the callback original_modal = self._modal_overlay self._modal_overlay = ModalOverlay() + if hasattr(original_modal.overlay, 'hide_event'): + original_modal.overlay.hide_event() if original_modal.callback is not None: original_modal.callback(result) return True @@ -602,6 +658,7 @@ class GuiApplication(GuiApplicationExt): # Strict mode: terminate UI if FPS drops too much if STRICT_MODE and fps < self._target_fps * FPS_CRITICAL_THRESHOLD: cloudlog.error(f"FPS dropped critically below {fps}. Shutting down UI.") + self.close_ffmpeg() os._exit(1) def _draw_touch_points(self): diff --git a/system/ui/lib/egl.py b/system/ui/lib/egl.py index d119a8a832..69236482b0 100644 --- a/system/ui/lib/egl.py +++ b/system/ui/lib/egl.py @@ -128,8 +128,12 @@ def init_egl() -> bool: def create_egl_image(width: int, height: int, stride: int, fd: int, uv_offset: int) -> EGLImage | None: assert _egl.initialized, "EGL not initialized" - # Duplicate fd since EGL needs it - dup_fd = os.dup(fd) + try: + # Duplicate fd since EGL needs it + dup_fd = os.dup(fd) + except OSError as e: + cloudlog.exception(f"Failed to duplicate frame fd when creating EGL image: {e}") + return None # Create image attributes for EGL img_attrs = [ diff --git a/system/ui/lib/scroll_panel2.py b/system/ui/lib/scroll_panel2.py index 8d9caadfdd..00ef95cc8b 100644 --- a/system/ui/lib/scroll_panel2.py +++ b/system/ui/lib/scroll_panel2.py @@ -8,7 +8,7 @@ from openpilot.system.ui.lib.application import gui_app, MouseEvent from openpilot.system.hardware import TICI from collections import deque -MIN_VELOCITY = 2 # px/s, changes from auto scroll to steady state +MIN_VELOCITY = 10 # px/s, changes from auto scroll to steady state MIN_VELOCITY_FOR_CLICKING = 2 * 60 # px/s, accepts clicks while auto scrolling below this velocity MIN_DRAG_PIXELS = 12 AUTO_SCROLL_TC_SNAP = 0.025 @@ -67,16 +67,18 @@ class GuiScrollPanel2: print() return self.get_offset() + def _get_offset_bounds(self, bounds_size: float, content_size: float) -> tuple[float, float]: + """Returns (max_offset, min_offset) for the given bounds and content size.""" + return 0.0, min(0.0, bounds_size - content_size) + def _update_state(self, bounds_size: float, content_size: float) -> None: """Runs per render frame, independent of mouse events. Updates auto-scrolling state and velocity.""" if self._state == ScrollState.AUTO_SCROLL: + max_offset, min_offset = self._get_offset_bounds(bounds_size, content_size) # simple exponential return if out of bounds - out_of_bounds = self.get_offset() > 0 or self.get_offset() < (bounds_size - content_size) + out_of_bounds = self.get_offset() > max_offset or self.get_offset() < min_offset if out_of_bounds and self._handle_out_of_bounds: - if self.get_offset() < (bounds_size - content_size): # too far right - target = bounds_size - content_size - else: # too far left - target = 0.0 + target = max_offset if self.get_offset() > max_offset else min_offset dt = rl.get_frame_time() or 1e-6 factor = 1.0 - math.exp(-BOUNCE_RETURN_RATE * dt) @@ -88,6 +90,7 @@ class GuiScrollPanel2: # Steady once we are close enough to the target if abs(dist) < 1 and abs(self._velocity) < MIN_VELOCITY: self.set_offset(target) + self._velocity = 0.0 self._state = ScrollState.STEADY elif abs(self._velocity) < MIN_VELOCITY: @@ -102,7 +105,9 @@ class GuiScrollPanel2: def _handle_mouse_event(self, mouse_event: MouseEvent, bounds: rl.Rectangle, bounds_size: float, content_size: float) -> None: - out_of_bounds = self.get_offset() > 0 or self.get_offset() < (bounds_size - content_size) + max_offset, min_offset = self._get_offset_bounds(bounds_size, content_size) + # simple exponential return if out of bounds + out_of_bounds = self.get_offset() > max_offset or self.get_offset() < min_offset if DEBUG: print('Mouse event:', mouse_event) @@ -201,8 +206,8 @@ class GuiScrollPanel2: def _get_mouse_pos(self, mouse_event: MouseEvent) -> float: return mouse_event.pos.x if self._horizontal else mouse_event.pos.y - def get_offset(self) -> int: - return round(self._offset.x if self._horizontal else self._offset.y) + def get_offset(self) -> float: + return self._offset.x if self._horizontal else self._offset.y def set_offset(self, value: float) -> None: if self._horizontal: diff --git a/system/ui/mici_setup.py b/system/ui/mici_setup.py index 316e6c4a8b..4435bd95e3 100755 --- a/system/ui/mici_setup.py +++ b/system/ui/mici_setup.py @@ -244,7 +244,7 @@ class TermsPage(Widget): pass def _render(self, _): - scroll_offset = self._scroll_panel.update(self._rect, self._content_height + self._continue_button.rect.height + 16) + scroll_offset = round(self._scroll_panel.update(self._rect, self._content_height + self._continue_button.rect.height + 16)) if scroll_offset <= self._scrolled_down_offset: # don't show back if not enabled diff --git a/system/ui/widgets/__init__.py b/system/ui/widgets/__init__.py index 95858ec1b3..546c682f33 100644 --- a/system/ui/widgets/__init__.py +++ b/system/ui/widgets/__init__.py @@ -104,46 +104,53 @@ class Widget(abc.ABC): # Keep track of whether mouse down started within the widget's rectangle if self.enabled and self.__was_awake: - for mouse_event in gui_app.mouse_events: - if not self._multi_touch and mouse_event.slot != 0: - continue - - # Ignores touches/presses that start outside our rect - # Allows touch to leave the rect and come back in focus if mouse did not release - if mouse_event.left_pressed and self._touch_valid(): - if rl.check_collision_point_rec(mouse_event.pos, self._hit_rect): - self._handle_mouse_press(mouse_event.pos) - self.__is_pressed[mouse_event.slot] = True - self.__tracking_is_pressed[mouse_event.slot] = True - self._handle_mouse_event(mouse_event) - - # Callback such as scroll panel signifies user is scrolling - elif not self._touch_valid(): - self.__is_pressed[mouse_event.slot] = False - self.__tracking_is_pressed[mouse_event.slot] = False - - elif mouse_event.left_released: - self._handle_mouse_event(mouse_event) - if self.__is_pressed[mouse_event.slot] and rl.check_collision_point_rec(mouse_event.pos, self._hit_rect): - self._handle_mouse_release(mouse_event.pos) - self.__is_pressed[mouse_event.slot] = False - self.__tracking_is_pressed[mouse_event.slot] = False - - # Mouse/touch is still within our rect - elif rl.check_collision_point_rec(mouse_event.pos, self._hit_rect): - if self.__tracking_is_pressed[mouse_event.slot]: - self.__is_pressed[mouse_event.slot] = True - self._handle_mouse_event(mouse_event) - - # Mouse/touch left our rect but may come back into focus later - elif not rl.check_collision_point_rec(mouse_event.pos, self._hit_rect): - self.__is_pressed[mouse_event.slot] = False - self._handle_mouse_event(mouse_event) + self._process_mouse_events() self.__was_awake = device.awake return ret + def _process_mouse_events(self) -> None: + hit_rect = self._hit_rect + touch_valid = self._touch_valid() + + for mouse_event in gui_app.mouse_events: + if not self._multi_touch and mouse_event.slot != 0: + continue + + mouse_in_rect = rl.check_collision_point_rec(mouse_event.pos, hit_rect) + # Ignores touches/presses that start outside our rect + # Allows touch to leave the rect and come back in focus if mouse did not release + if mouse_event.left_pressed and touch_valid: + if mouse_in_rect: + self._handle_mouse_press(mouse_event.pos) + self.__is_pressed[mouse_event.slot] = True + self.__tracking_is_pressed[mouse_event.slot] = True + self._handle_mouse_event(mouse_event) + + # Callback such as scroll panel signifies user is scrolling + elif not touch_valid: + self.__is_pressed[mouse_event.slot] = False + self.__tracking_is_pressed[mouse_event.slot] = False + + elif mouse_event.left_released: + self._handle_mouse_event(mouse_event) + if self.__is_pressed[mouse_event.slot] and mouse_in_rect: + self._handle_mouse_release(mouse_event.pos) + self.__is_pressed[mouse_event.slot] = False + self.__tracking_is_pressed[mouse_event.slot] = False + + # Mouse/touch is still within our rect + elif mouse_in_rect: + if self.__tracking_is_pressed[mouse_event.slot]: + self.__is_pressed[mouse_event.slot] = True + self._handle_mouse_event(mouse_event) + + # Mouse/touch left our rect but may come back into focus later + elif not mouse_in_rect: + self.__is_pressed[mouse_event.slot] = False + self._handle_mouse_event(mouse_event) + @abc.abstractmethod def _render(self, rect: rl.Rectangle) -> bool | int | None: """Render the widget within the given rectangle.""" @@ -359,6 +366,10 @@ class NavWidget(Widget, abc.ABC): self._nav_bar.set_position(bar_x, round(self._nav_bar_y_filter.x)) self._nav_bar.render() + # draw black above widget when dismissing + if self._rect.y > 0: + rl.draw_rectangle(int(self._rect.x), 0, int(self._rect.width), int(self._rect.y), rl.BLACK) + return ret def show_event(self): diff --git a/system/ui/widgets/label.py b/system/ui/widgets/label.py index 35e2708e62..97b293083d 100644 --- a/system/ui/widgets/label.py +++ b/system/ui/widgets/label.py @@ -179,11 +179,11 @@ class MiciLabel(Widget): if self._needs_scroll: # draw black fade on left and right fade_width = 20 - rl.draw_rectangle_gradient_h(int(rect.x + rect.width - fade_width), int(rect.y), fade_width, int(rect.height), rl.Color(0, 0, 0, 0), rl.BLACK) + rl.draw_rectangle_gradient_h(int(rect.x + rect.width - fade_width), int(rect.y), fade_width, int(rect.height), rl.BLANK, rl.BLACK) if self._scroll_state != ScrollState.STARTING: - rl.draw_rectangle_gradient_h(int(rect.x), int(rect.y), fade_width, int(rect.height), rl.BLACK, rl.Color(0, 0, 0, 0)) + rl.draw_rectangle_gradient_h(int(rect.x), int(rect.y), fade_width, int(rect.height), rl.BLACK, rl.BLANK) - rl.end_scissor_mode() + rl.end_scissor_mode() # TODO: This should be a Widget class @@ -412,6 +412,7 @@ class UnifiedLabel(Widget): max_width: int | None = None, elide: bool = True, wrap_text: bool = True, + scroll: bool = False, line_height: float = 1.0, letter_spacing: float = 0.0): super().__init__() @@ -426,10 +427,23 @@ class UnifiedLabel(Widget): self._max_width = max_width self._elide = elide self._wrap_text = wrap_text + self._scroll = scroll self._line_height = line_height * 0.9 self._letter_spacing = letter_spacing # 0.1 = 10% self._spacing_pixels = font_size * letter_spacing + # Scroll state + self._scroll = scroll + self._needs_scroll = False + self._scroll_offset = 0 + self._scroll_pause_t: float | None = None + self._scroll_state: ScrollState = ScrollState.STARTING + + # Scroll mode does not support eliding or multiline wrapping + if self._scroll: + self._elide = False + self._wrap_text = False + # Cached data self._cached_text: str | None = None self._cached_wrapped_lines: list[str] = [] @@ -446,7 +460,7 @@ class UnifiedLabel(Widget): def set_text(self, text: str | Callable[[], str]): """Update the text content.""" self._text = text - self._cached_text = None # Invalidate cache + # No need to update cache here, will be done on next render if needed @property def text(self) -> str: @@ -463,15 +477,17 @@ class UnifiedLabel(Widget): def set_font_size(self, size: int): """Update the font size.""" - self._font_size = size - self._spacing_pixels = size * self._letter_spacing # Recalculate spacing - self._cached_text = None # Invalidate cache + if self._font_size != size: + self._font_size = size + self._spacing_pixels = size * self._letter_spacing # Recalculate spacing + self._cached_text = None # Invalidate cache def set_letter_spacing(self, letter_spacing: float): """Update letter spacing (as percentage, e.g., 0.1 = 10%).""" - self._letter_spacing = letter_spacing - self._spacing_pixels = self._font_size * letter_spacing - self._cached_text = None # Invalidate cache + if self._letter_spacing != letter_spacing: + self._letter_spacing = letter_spacing + self._spacing_pixels = self._font_size * letter_spacing + self._cached_text = None # Invalidate cache def set_font_weight(self, font_weight: FontWeight): """Update the font weight.""" @@ -488,6 +504,12 @@ class UnifiedLabel(Widget): """Update the vertical text alignment.""" self._alignment_vertical = alignment_vertical + def reset_scroll(self): + """Reset scroll state to initial position.""" + self._scroll_offset = 0 + self._scroll_pause_t = None + self._scroll_state = ScrollState.STARTING + def set_max_width(self, max_width: int | None): """Set the maximum width constraint for wrapping/eliding.""" if self._max_width != max_width: @@ -526,6 +548,9 @@ class UnifiedLabel(Widget): # Elide lines if needed (for width constraint) self._cached_wrapped_lines = [self._elide_line(line, content_width) for line in self._cached_wrapped_lines] + if self._scroll: + self._cached_wrapped_lines = self._cached_wrapped_lines[:1] # Only first line for scrolling + # Process each line: measure and find emojis self._cached_line_sizes = [] self._cached_line_emojis = [] @@ -538,6 +563,11 @@ class UnifiedLabel(Widget): size = rl.Vector2(0, self._font_size * FONT_SCALE) else: size = measure_text_cached(self._font, line, self._font_size, self._spacing_pixels) + + # This is the only line + if self._scroll: + self._needs_scroll = size.x > content_width + self._cached_line_sizes.append(size) # Calculate total height @@ -597,13 +627,13 @@ class UnifiedLabel(Widget): return self._cached_total_height return 0.0 - def _render(self, rect: rl.Rectangle): + def _render(self, _): """Render the label.""" - if rect.width <= 0 or rect.height <= 0: + if self._rect.width <= 0 or self._rect.height <= 0: return # Determine available width - available_width = rect.width + available_width = self._rect.width if self._max_width is not None: available_width = min(available_width, self._max_width) @@ -631,7 +661,7 @@ class UnifiedLabel(Widget): line_height_needed = size.y * self._line_height # Check if this line fits - if current_height + line_height_needed > rect.height: + if current_height + line_height_needed > self._rect.height: # This line doesn't fit if len(visible_lines) == 0: # First line doesn't fit by height - still show it (will be clipped by scissor if needed) @@ -675,51 +705,92 @@ class UnifiedLabel(Widget): # Calculate vertical alignment offset if self._alignment_vertical == rl.GuiTextAlignmentVertical.TEXT_ALIGN_TOP: - start_y = rect.y + start_y = self._rect.y elif self._alignment_vertical == rl.GuiTextAlignmentVertical.TEXT_ALIGN_BOTTOM: - start_y = rect.y + rect.height - total_visible_height + start_y = self._rect.y + self._rect.height - total_visible_height else: # TEXT_ALIGN_MIDDLE - start_y = rect.y + (rect.height - total_visible_height) / 2 + start_y = self._rect.y + (self._rect.height - total_visible_height) / 2 + + # Only scissor when we know there is a single scrolling line + # Pad a little since descenders like g or j may overflow below rect from font_scale + if self._needs_scroll: + rl.begin_scissor_mode(int(self._rect.x), int(self._rect.y - self._font_size / 2), int(self._rect.width), int(self._rect.height + self._font_size)) # Render each line current_y = start_y for idx, (line, size, emojis) in enumerate(zip(visible_lines, visible_sizes, visible_emojis, strict=True)): - # Calculate horizontal position - if self._alignment == rl.GuiTextAlignment.TEXT_ALIGN_LEFT: - line_x = rect.x + self._text_padding - elif self._alignment == rl.GuiTextAlignment.TEXT_ALIGN_CENTER: - line_x = rect.x + (rect.width - size.x) / 2 - elif self._alignment == rl.GuiTextAlignment.TEXT_ALIGN_RIGHT: - line_x = rect.x + rect.width - size.x - self._text_padding + if self._needs_scroll: + if self._scroll_state == ScrollState.STARTING: + if self._scroll_pause_t is None: + self._scroll_pause_t = rl.get_time() + 2.0 + if rl.get_time() >= self._scroll_pause_t: + self._scroll_state = ScrollState.SCROLLING + self._scroll_pause_t = None + + elif self._scroll_state == ScrollState.SCROLLING: + self._scroll_offset -= 0.8 / 60. * gui_app.target_fps + # don't fully hide + if self._scroll_offset <= -size.x - self._rect.width / 3: + self._scroll_offset = 0 + self._scroll_state = ScrollState.STARTING + self._scroll_pause_t = None else: - line_x = rect.x + self._text_padding + self.reset_scroll() - # Render line with emojis - line_pos = rl.Vector2(line_x, current_y) - prev_index = 0 + self._render_line(line, size, emojis, current_y) - for start, end, emoji in emojis: - # Draw text before emoji - text_before = line[prev_index:start] - if text_before: - rl.draw_text_ex(self._font, text_before, line_pos, self._font_size, self._spacing_pixels, self._text_color) - width_before = measure_text_cached(self._font, text_before, self._font_size, self._spacing_pixels) - line_pos.x += width_before.x - - # Draw emoji - tex = emoji_tex(emoji) - emoji_scale = self._font_size / tex.height * FONT_SCALE - rl.draw_texture_ex(tex, line_pos, 0.0, emoji_scale, self._text_color) - # Emoji width is font_size * FONT_SCALE (as per measure_text_cached) - line_pos.x += self._font_size * FONT_SCALE - prev_index = end - - # Draw remaining text after last emoji - text_after = line[prev_index:] - if text_after: - rl.draw_text_ex(self._font, text_after, line_pos, self._font_size, self._spacing_pixels, self._text_color) + # Draw 2nd instance for scrolling + if self._needs_scroll and self._scroll_state != ScrollState.STARTING: + text2_scroll_offset = size.x + self._rect.width / 3 + self._render_line(line, size, emojis, current_y, text2_scroll_offset) # Move to next line (if not last line) if idx < len(visible_lines) - 1: # Use current line's height * line_height for spacing to next line current_y += size.y * self._line_height + + if self._needs_scroll: + # draw black fade on left and right + fade_width = 20 + rl.draw_rectangle_gradient_h(int(self._rect.x + self._rect.width - fade_width), int(self._rect.y), fade_width, int(self._rect.height), rl.BLANK, rl.BLACK) + if self._scroll_state != ScrollState.STARTING: + rl.draw_rectangle_gradient_h(int(self._rect.x), int(self._rect.y), fade_width, int(self._rect.height), rl.BLACK, rl.BLANK) + + rl.end_scissor_mode() + + def _render_line(self, line, size, emojis, current_y, x_offset=0.0): + # Calculate horizontal position + if self._alignment == rl.GuiTextAlignment.TEXT_ALIGN_LEFT: + line_x = self._rect.x + self._text_padding + elif self._alignment == rl.GuiTextAlignment.TEXT_ALIGN_CENTER: + line_x = self._rect.x + (self._rect.width - size.x) / 2 + elif self._alignment == rl.GuiTextAlignment.TEXT_ALIGN_RIGHT: + line_x = self._rect.x + self._rect.width - size.x - self._text_padding + else: + line_x = self._rect.x + self._text_padding + line_x += self._scroll_offset + x_offset + + # Render line with emojis + line_pos = rl.Vector2(line_x, current_y) + prev_index = 0 + + for start, end, emoji in emojis: + # Draw text before emoji + text_before = line[prev_index:start] + if text_before: + rl.draw_text_ex(self._font, text_before, line_pos, self._font_size, self._spacing_pixels, self._text_color) + width_before = measure_text_cached(self._font, text_before, self._font_size, self._spacing_pixels) + line_pos.x += width_before.x + + # Draw emoji + tex = emoji_tex(emoji) + emoji_scale = self._font_size / tex.height * FONT_SCALE + rl.draw_texture_ex(tex, line_pos, 0.0, emoji_scale, self._text_color) + # Emoji width is font_size * FONT_SCALE (as per measure_text_cached) + line_pos.x += self._font_size * FONT_SCALE + prev_index = end + + # Draw remaining text after last emoji + text_after = line[prev_index:] + if text_after: + rl.draw_text_ex(self._font, text_after, line_pos, self._font_size, self._spacing_pixels, self._text_color) diff --git a/system/ui/widgets/mici_keyboard.py b/system/ui/widgets/mici_keyboard.py index a4f4c7d09b..7459dc5731 100644 --- a/system/ui/widgets/mici_keyboard.py +++ b/system/ui/widgets/mici_keyboard.py @@ -4,7 +4,7 @@ import numpy as np from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos, MouseEvent from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.widgets import Widget -from openpilot.common.filter_simple import BounceFilter +from openpilot.common.filter_simple import BounceFilter, FirstOrderFilter CHAR_FONT_SIZE = 42 CHAR_NEAR_FONT_SIZE = CHAR_FONT_SIZE * 2 @@ -204,6 +204,7 @@ class MiciKeyboard(Widget): self._text: str = "" self._bg_scale_filter = BounceFilter(1.0, 0.1 * ANIMATION_SCALE, 1 / gui_app.target_fps) + self._selected_key_filter = FirstOrderFilter(0.0, 0.075 * ANIMATION_SCALE, 1 / gui_app.target_fps) def get_candidate_character(self) -> str: # return str of character about to be added to text @@ -309,6 +310,9 @@ class MiciKeyboard(Widget): self._text += ' ' def _update_state(self): + # update selected key filter + self._selected_key_filter.update(self._closest_key[0] is not None) + # unselect key after animation plays if self._unselect_key_t is not None and rl.get_time() > self._unselect_key_t: self._closest_key = (None, float('inf')) @@ -335,8 +339,9 @@ class MiciKeyboard(Widget): key.set_font_size(SELECTED_CHAR_FONT_SIZE) # draw black circle behind selected key + circle_alpha = int(self._selected_key_filter.x * 225) rl.draw_circle_gradient(int(key_x + key.rect.width / 2), int(key_y + key.rect.height / 2), - SELECTED_CHAR_FONT_SIZE, rl.Color(0, 0, 0, 225), rl.BLANK) + SELECTED_CHAR_FONT_SIZE, rl.Color(0, 0, 0, circle_alpha), rl.BLANK) else: # move other keys away from selected key a bit dx = key.original_position.x - self._closest_key[0].original_position.x diff --git a/system/ui/widgets/scroller.py b/system/ui/widgets/scroller.py index 9a04e84257..72f76d90c4 100644 --- a/system/ui/widgets/scroller.py +++ b/system/ui/widgets/scroller.py @@ -124,7 +124,7 @@ class Scroller(Widget): self.scroll_panel.set_enabled(scroll_enabled and self.enabled) self.scroll_panel.update(self._rect, content_size) if not self._snap_items: - return self.scroll_panel.get_offset() + return round(self.scroll_panel.get_offset()) # Snap closest item to center center_pos = self._rect.x + self._rect.width / 2 if self._horizontal else self._rect.y + self._rect.height / 2 @@ -224,12 +224,15 @@ class Scroller(Widget): # Scale each element around its own origin when scrolling scale = self._zoom_filter.x - rl.rl_push_matrix() - rl.rl_scalef(scale, scale, 1.0) - rl.rl_translatef((1 - scale) * (x + item.rect.width / 2) / scale, - (1 - scale) * (y + item.rect.height / 2) / scale, 0) - item.render() - rl.rl_pop_matrix() + if scale != 1.0: + rl.rl_push_matrix() + rl.rl_scalef(scale, scale, 1.0) + rl.rl_translatef((1 - scale) * (x + item.rect.width / 2) / scale, + (1 - scale) * (y + item.rect.height / 2) / scale, 0) + item.render() + rl.rl_pop_matrix() + else: + item.render() # Draw scroll indicator if SCROLL_BAR and not self._horizontal and len(visible_items) > 0: diff --git a/system/updated/casync/casync.py b/system/updated/casync/casync.py index 7a3303a9e9..79ac26f1c6 100755 --- a/system/updated/casync/casync.py +++ b/system/updated/casync/casync.py @@ -99,7 +99,7 @@ class DirectoryTarChunkReader(BinaryChunkReader): create_casync_tar_package(pathlib.Path(path), pathlib.Path(cache_file)) self.f = open(cache_file, "rb") - return super().__init__(self.f) + super().__init__(self.f) def __del__(self): self.f.close() diff --git a/system/updated/tests/test_base.py b/system/updated/tests/test_base.py index 699a0f0bd3..c4894f2711 100644 --- a/system/updated/tests/test_base.py +++ b/system/updated/tests/test_base.py @@ -133,7 +133,7 @@ class TestBaseUpdate: class ParamsBaseUpdateTest(TestBaseUpdate): def _test_finalized_update(self, branch, version, agnos_version, release_notes): assert self.params.get("UpdaterNewDescription").startswith(f"{version} / {branch}") - assert self.params.get("UpdaterNewReleaseNotes") == f"{release_notes}\n" + assert self.params.get("UpdaterNewReleaseNotes") == f"{release_notes}\n".encode() super()._test_finalized_update(branch, version, agnos_version, release_notes) def send_check_for_updates_signal(self, updated: ManagerProcess): diff --git a/system/version.py b/system/version.py index 84d6b75591..8a0e2da3e2 100755 --- a/system/version.py +++ b/system/version.py @@ -13,7 +13,7 @@ from openpilot.common.git import get_commit, get_origin, get_branch, get_short_b RELEASE_SP_BRANCHES = ['release-c3', 'release', 'release-tizi', 'release-tici', 'release-tizi-staging', 'release-tici-staging'] TESTED_SP_BRANCHES = ['staging-c3', 'staging-c3-new', 'staging'] MASTER_SP_BRANCHES = ['master'] -RELEASE_BRANCHES = ['release-tizi-staging', 'release-tici', 'release-tizi', 'nightly'] +RELEASE_BRANCHES = ['release-tizi-staging', 'release-mici-staging', 'release-tizi', 'release-mici', 'nightly'] TESTED_BRANCHES = RELEASE_BRANCHES + ['devel-staging', 'nightly-dev'] + RELEASE_SP_BRANCHES + TESTED_SP_BRANCHES SP_BRANCH_MIGRATIONS = { diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc index eb0af5b64a..b5a68c6b26 100644 --- a/tools/cabana/binaryview.cc +++ b/tools/cabana/binaryview.cc @@ -275,16 +275,13 @@ void BinaryViewModel::refresh() { row_count = can->lastMessage(msg_id).dat.size(); items.resize(row_count * column_count); } - int valid_rows = std::min(can->lastMessage(msg_id).dat.size(), row_count); - for (int i = 0; i < valid_rows * column_count; ++i) { - items[i].valid = true; - } endResetModel(); updateState(); } void BinaryViewModel::updateItem(int row, int col, uint8_t val, const QColor &color) { auto &item = items[row * column_count + col]; + item.valid = true; if (item.val != val || item.bg_color != color) { item.val = val; item.bg_color = color; diff --git a/tools/cabana/chart/chartswidget.cc b/tools/cabana/chart/chartswidget.cc index 3e9e452b90..aba25dcf83 100644 --- a/tools/cabana/chart/chartswidget.cc +++ b/tools/cabana/chart/chartswidget.cc @@ -322,6 +322,32 @@ void ChartsWidget::splitChart(ChartView *src_chart) { } } +QStringList ChartsWidget::serializeChartIds() const { + QStringList chart_ids; + for (auto c : charts) { + QStringList ids; + for (const auto& s : c->sigs) + ids += QString("%1|%2").arg(s.msg_id.toString(), s.sig->name); + chart_ids += ids.join(','); + } + std::reverse(chart_ids.begin(), chart_ids.end()); + return chart_ids; +} + +void ChartsWidget::restoreChartsFromIds(const QStringList& chart_ids) { + for (const auto& chart_id : chart_ids) { + int index = 0; + for (const auto& part : chart_id.split(',')) { + const auto sig_parts = part.split('|'); + if (sig_parts.size() != 2) continue; + MessageId msg_id = MessageId::fromString(sig_parts[0]); + if (auto* msg = dbc()->msg(msg_id)) + if (auto* sig = msg->sig(sig_parts[1])) + showChart(msg_id, sig, true, index++ > 0); + } + } +} + void ChartsWidget::setColumnCount(int n) { n = std::clamp(n, 1, MAX_COLUMN_COUNT); if (column_count != n) { diff --git a/tools/cabana/chart/chartswidget.h b/tools/cabana/chart/chartswidget.h index 46e7f546b0..f87b1276c5 100644 --- a/tools/cabana/chart/chartswidget.h +++ b/tools/cabana/chart/chartswidget.h @@ -43,6 +43,8 @@ public: ChartsWidget(QWidget *parent = nullptr); void showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge); inline bool hasSignal(const MessageId &id, const cabana::Signal *sig) { return findChart(id, sig) != nullptr; } + QStringList serializeChartIds() const; + void restoreChartsFromIds(const QStringList &chart_ids); public slots: void setColumnCount(int n); diff --git a/tools/cabana/dbc/dbc.h b/tools/cabana/dbc/dbc.h index d2b25bc5f2..134d88a919 100644 --- a/tools/cabana/dbc/dbc.h +++ b/tools/cabana/dbc/dbc.h @@ -20,6 +20,12 @@ struct MessageId { return QString("%1:%2").arg(source).arg(QString::number(address, 16).toUpper()); } + inline static MessageId fromString(const QString &str) { + auto parts = str.split(':'); + if (parts.size() != 2) return {}; + return MessageId{.source = uint8_t(parts[0].toUInt()), .address = parts[1].toUInt(nullptr, 16)}; + } + bool operator==(const MessageId &other) const { return source == other.source && address == other.address; } diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 4eda46f37b..35492c8efa 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -118,10 +118,7 @@ void DetailWidget::showTabBarContextMenu(const QPoint &pt) { } } -void DetailWidget::setMessage(const MessageId &message_id) { - if (std::exchange(msg_id, message_id) == message_id) return; - - tabbar->blockSignals(true); +int DetailWidget::findOrAddTab(const MessageId& message_id) { int index = tabbar->count() - 1; for (/**/; index >= 0; --index) { if (tabbar->tabData(index).value() == message_id) break; @@ -131,6 +128,14 @@ void DetailWidget::setMessage(const MessageId &message_id) { tabbar->setTabData(index, QVariant::fromValue(message_id)); tabbar->setTabToolTip(index, msgName(message_id)); } + return index; +} + +void DetailWidget::setMessage(const MessageId &message_id) { + if (std::exchange(msg_id, message_id) == message_id) return; + + tabbar->blockSignals(true); + int index = findOrAddTab(message_id); tabbar->setCurrentIndex(index); tabbar->blockSignals(false); @@ -142,6 +147,29 @@ void DetailWidget::setMessage(const MessageId &message_id) { setUpdatesEnabled(true); } +std::pair DetailWidget::serializeMessageIds() const { + QStringList msgs; + for (int i = 0; i < tabbar->count(); ++i) { + MessageId id = tabbar->tabData(i).value(); + msgs.append(id.toString()); + } + return std::make_pair(msg_id.toString(), msgs); +} + +void DetailWidget::restoreTabs(const QString active_msg_id, const QStringList& msg_ids) { + tabbar->blockSignals(true); + for (const auto& str_id : msg_ids) { + MessageId id = MessageId::fromString(str_id); + if (dbc()->msg(id) != nullptr) + findOrAddTab(id); + } + tabbar->blockSignals(false); + + auto active_id = MessageId::fromString(active_msg_id); + if (dbc()->msg(active_id) != nullptr) + setMessage(active_id); +} + void DetailWidget::refresh() { QStringList warnings; auto msg = dbc()->msg(msg_id); @@ -244,13 +272,13 @@ CenterWidget::CenterWidget(QWidget *parent) : QWidget(parent) { main_layout->addWidget(welcome_widget = createWelcomeWidget()); } -void CenterWidget::setMessage(const MessageId &msg_id) { +DetailWidget* CenterWidget::ensureDetailWidget() { if (!detail_widget) { delete welcome_widget; welcome_widget = nullptr; layout()->addWidget(detail_widget = new DetailWidget(((MainWindow*)parentWidget())->charts_widget, this)); } - detail_widget->setMessage(msg_id); + return detail_widget; } void CenterWidget::clear() { diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index 6df164b442..0fe1535c7a 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -34,9 +34,12 @@ public: DetailWidget(ChartsWidget *charts, QWidget *parent); void setMessage(const MessageId &message_id); void refresh(); + std::pair serializeMessageIds() const; + void restoreTabs(const QString active_msg_id, const QStringList &msg_ids); private: void createToolBar(); + int findOrAddTab(const MessageId& message_id); void showTabBarContextMenu(const QPoint &pt); void editMsg(); void removeMsg(); @@ -60,7 +63,9 @@ class CenterWidget : public QWidget { Q_OBJECT public: CenterWidget(QWidget *parent); - void setMessage(const MessageId &msg_id); + void setMessage(const MessageId &message_id) { ensureDetailWidget()->setMessage(message_id); } + DetailWidget* getDetailWidget() { return detail_widget; } + DetailWidget* ensureDetailWidget(); void clear(); private: diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index d65fc5b760..1ea3733ed0 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -235,6 +235,8 @@ void MainWindow::DBCFileChanged() { title.push_back(tr("(%1) %2").arg(toString(dbc()->sources(f)), f->name())); } setWindowFilePath(title.join(" | ")); + + QTimer::singleShot(0, this, &::MainWindow::restoreSessionState); } void MainWindow::selectAndOpenStream() { @@ -311,11 +313,19 @@ void MainWindow::loadFromClipboard(SourceSet s, bool close_all) { } void MainWindow::openStream(AbstractStream *stream, const QString &dbc_file) { + if (can) { + QObject::connect(can, &QObject::destroyed, this, [=]() { startStream(stream, dbc_file); }); + can->deleteLater(); + } else { + startStream(stream, dbc_file); + } +} + +void MainWindow::startStream(AbstractStream *stream, QString dbc_file) { center_widget->clear(); delete messages_widget; delete video_splitter; - delete can; can = stream; can->setParent(this); // take ownership can->start(); @@ -563,6 +573,7 @@ void MainWindow::closeEvent(QCloseEvent *event) { settings.message_header_state = messages_widget->saveHeaderState(); } + saveSessionState(); QWidget::closeEvent(event); } @@ -607,6 +618,39 @@ void MainWindow::toggleFullScreen() { } } +void MainWindow::saveSessionState() { + settings.recent_dbc_file = ""; + settings.active_msg_id = ""; + settings.selected_msg_ids.clear(); + settings.active_charts.clear(); + + for (auto &f : dbc()->allDBCFiles()) + if (!f->isEmpty()) { settings.recent_dbc_file = f->filename; break; } + + if (auto *detail = center_widget->getDetailWidget()) { + auto [active_id, ids] = detail->serializeMessageIds(); + settings.active_msg_id = active_id; + settings.selected_msg_ids = ids; + } + if (charts_widget) + settings.active_charts = charts_widget->serializeChartIds(); +} + +void MainWindow::restoreSessionState() { + if (settings.recent_dbc_file.isEmpty() || dbc()->nonEmptyDBCCount() == 0) return; + + QString dbc_file; + for (auto& f : dbc()->allDBCFiles()) + if (!f->isEmpty()) { dbc_file = f->filename; break; } + if (dbc_file != settings.recent_dbc_file) return; + + if (!settings.selected_msg_ids.isEmpty()) + center_widget->ensureDetailWidget()->restoreTabs(settings.active_msg_id, settings.selected_msg_ids); + + if (charts_widget != nullptr && !settings.active_charts.empty()) + charts_widget->restoreChartsFromIds(settings.active_charts); +} + // HelpOverlay HelpOverlay::HelpOverlay(MainWindow *parent) : QWidget(parent) { setAttribute(Qt::WA_NoSystemBackground, true); diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index 9bc94c090f..92c2714ae7 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -44,6 +44,7 @@ signals: void updateProgressBar(uint64_t cur, uint64_t total, bool success); protected: + void startStream(AbstractStream *stream, QString dbc_file); bool eventFilter(QObject *obj, QEvent *event) override; void remindSaveChanges(); void closeFile(SourceSet s = SOURCE_ALL); @@ -72,6 +73,8 @@ protected: void updateLoadSaveMenus(); void createDockWidgets(); void eventsMerged(); + void saveSessionState(); + void restoreSessionState(); VideoWidget *video_widget = nullptr; QDockWidget *video_dock; diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index cccc9b6d9a..e7b1129a30 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -41,6 +41,10 @@ void settings_op(SettingOperation op) { op(s, "log_path", settings.log_path); op(s, "drag_direction", (int &)settings.drag_direction); op(s, "suppress_defined_signals", settings.suppress_defined_signals); + op(s, "recent_dbc_file", settings.recent_dbc_file); + op(s, "active_msg_id", settings.active_msg_id); + op(s, "selected_msg_ids", settings.selected_msg_ids); + op(s, "active_charts", settings.active_charts); } Settings::Settings() { diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h index e75c519ac7..7ab50d1494 100644 --- a/tools/cabana/settings.h +++ b/tools/cabana/settings.h @@ -46,6 +46,12 @@ public: QByteArray message_header_state; DragDirection drag_direction = MsbFirst; + // session data + QString recent_dbc_file; + QString active_msg_id; + QStringList selected_msg_ids; + QStringList active_charts; + signals: void changed(); }; diff --git a/tools/install_python_dependencies.sh b/tools/install_python_dependencies.sh index cdbaca32cf..c2db249cf2 100755 --- a/tools/install_python_dependencies.sh +++ b/tools/install_python_dependencies.sh @@ -1,5 +1,5 @@ #!/usr/bin/env bash -set -e +set -euo pipefail # Increase the pip timeout to handle TimeoutError export PIP_DEFAULT_TIMEOUT=200 @@ -10,7 +10,7 @@ cd "$ROOT" if ! command -v "uv" > /dev/null 2>&1; then echo "installing uv..." - curl -LsSf https://astral.sh/uv/install.sh | sh + curl -LsSf --retry 5 --retry-delay 5 --retry-all-errors https://astral.sh/uv/install.sh | sh UV_BIN="$HOME/.local/bin" PATH="$UV_BIN:$PATH" fi diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index ee9ee294bb..f5418be81a 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -1,4 +1,5 @@ import os +import io import posixpath import socket from functools import cache @@ -41,9 +42,17 @@ def file_exists(fn): return URLFile(fn).get_length_online() != -1 return os.path.exists(fn) +class DiskFile(io.BufferedReader): + def get_multi_range(self, ranges: list[tuple[int, int]]) -> list[bytes]: + parts = [] + for r in ranges: + self.seek(r[0]) + parts.append(self.read(r[1] - r[0])) + return parts -def FileReader(fn, debug=False): +def FileReader(fn): fn = resolve_name(fn) if fn.startswith(("http://", "https://")): - return URLFile(fn, debug=debug) - return open(fn, "rb") + return URLFile(fn) + else: + return DiskFile(open(fn, "rb")) diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 8d84cdbd5d..f9a90490b9 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -181,6 +181,8 @@ def auto_source(identifier: str, sources: list[Source], default_mode: ReadMode) # We've found all files, return them if len(needed_seg_idxs) == 0: return cast(list[str], list(valid_files.values())) + else: + raise FileNotFoundError(f"Did not find {fn} for seg idxs {needed_seg_idxs} of {sr.route_name}") except Exception as e: exceptions[source.__name__] = e diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 31c1e0ff11..c791444f74 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -1,14 +1,15 @@ +import re import logging import os import socket -import time from hashlib import sha256 from urllib3 import PoolManager, Retry from urllib3.response import BaseHTTPResponse from urllib3.util import Timeout -from openpilot.common.utils import atomic_write_in_dir +from openpilot.common.utils import atomic_write from openpilot.system.hardware.hw import Paths +from urllib3.exceptions import MaxRetryError # Cache chunk size K = 1000 @@ -40,12 +41,11 @@ class URLFile: URLFile._pool_manager = PoolManager(num_pools=10, maxsize=100, socket_options=socket_options, retries=retries) return URLFile._pool_manager - def __init__(self, url: str, timeout: int = 10, debug: bool = False, cache: bool | None = None): + def __init__(self, url: str, timeout: int = 10, cache: bool | None = None): self._url = url self._timeout = Timeout(connect=timeout, read=timeout) self._pos = 0 self._length: int | None = None - self._debug = debug # True by default, false if FILEREADER_CACHE is defined, but can be overwritten by the cache input self._force_download = not int(os.environ.get("FILEREADER_CACHE", "0")) if cache is not None: @@ -61,7 +61,10 @@ class URLFile: pass def _request(self, method: str, url: str, headers: dict[str, str] | None = None) -> BaseHTTPResponse: - return URLFile.pool_manager().request(method, url, timeout=self._timeout, headers=headers) + try: + return URLFile.pool_manager().request(method, url, timeout=self._timeout, headers=headers) + except MaxRetryError as e: + raise URLFileException(f"Failed to {method} {url}: {e}") from e def get_length_online(self) -> int: response = self._request('HEAD', self._url) @@ -83,7 +86,7 @@ class URLFile: self._length = self.get_length_online() if not self._force_download and self._length != -1: - with atomic_write_in_dir(file_length_path, mode="w", overwrite=True) as file_length: + with atomic_write(file_length_path, mode="w", overwrite=True) as file_length: file_length.write(str(self._length)) return self._length @@ -106,7 +109,7 @@ class URLFile: # If we don't have a file, download it if not os.path.exists(full_path): data = self.read_aux(ll=CHUNK_SIZE) - with atomic_write_in_dir(full_path, mode="wb", overwrite=True) as new_cached_file: + with atomic_write(full_path, mode="wb", overwrite=True) as new_cached_file: new_cached_file.write(data) else: with open(full_path, "rb") as cached_file: @@ -120,39 +123,45 @@ class URLFile: return response def read_aux(self, ll: int | None = None) -> bytes: - download_range = False - headers = {} - if self._pos != 0 or ll is not None: - if ll is None: - end = self.get_length() - 1 - else: - end = min(self._pos + ll, self.get_length()) - 1 - if self._pos >= end: - return b"" - headers['Range'] = f"bytes={self._pos}-{end}" - download_range = True + if ll is None: + length = self.get_length() + if length == -1: + raise URLFileException(f"Remote file is empty or doesn't exist: {self._url}") + end = length + else: + end = self._pos + ll + data = self.get_multi_range([(self._pos, end)]) + self._pos += len(data[0]) + return data[0] - if self._debug: - t1 = time.monotonic() + def get_multi_range(self, ranges: list[tuple[int, int]]) -> list[bytes]: + # HTTP range requests are inclusive + assert all(e > s for s, e in ranges), "Range end must be greater than start" + rs = [f"{s}-{e-1}" for s, e in ranges if e > s] - response = self._request('GET', self._url, headers=headers) - ret = response.data + r = self._request("GET", self._url, headers={"Range": "bytes=" + ",".join(rs)}) + if r.status not in [200, 206]: + raise URLFileException(f"Expected 206 or 200 response {r.status} ({self._url})") - if self._debug: - t2 = time.monotonic() - if t2 - t1 > 0.1: - print(f"get {self._url} {headers!r} {t2 - t1:.3f} slow") + ctype = (r.headers.get("content-type") or "").lower() + if "multipart/byteranges" not in ctype: + return [r.data,] - response_code = response.status - if response_code == 416: # Requested Range Not Satisfiable - raise URLFileException(f"Error, range out of bounds {response_code} {headers} ({self._url}): {repr(ret)[:500]}") - if download_range and response_code != 206: # Partial Content - raise URLFileException(f"Error, requested range but got unexpected response {response_code} {headers} ({self._url}): {repr(ret)[:500]}") - if (not download_range) and response_code != 200: # OK - raise URLFileException(f"Error {response_code} {headers} ({self._url}): {repr(ret)[:500]}") + m = re.search(r'boundary="?([^";]+)"?', ctype) + if not m: + raise URLFileException(f"Missing multipart boundary ({self._url})") + boundary = m.group(1).encode() - self._pos += len(ret) - return ret + parts = [] + for chunk in r.data.split(b"--" + boundary): + if b"\r\n\r\n" not in chunk: + continue + payload = chunk.split(b"\r\n\r\n", 1)[1].rstrip(b"\r\n") + if payload and payload != b"--": + parts.append(payload) + if len(parts) != len(ranges): + raise URLFileException(f"Expected {len(ranges)} parts, got {len(parts)} ({self._url})") + return parts def seek(self, pos: int) -> None: self._pos = pos diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index bdbdb3e841..a57c8a125d 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -117,7 +117,12 @@ void ConsoleUI::initWindows() { w[Win::Log] = newwin(log_height - 2, max_width - 2 * BORDER_SIZE, 18, BORDER_SIZE); scrollok(w[Win::Log], true); } - w[Win::Help] = newwin(5, max_width - (2 * BORDER_SIZE), max_height - 6, BORDER_SIZE); + if (max_height >= 23) { + w[Win::Help] = newwin(5, max_width - (2 * BORDER_SIZE), max_height - 6, BORDER_SIZE); + } else if (max_height >= 17) { + w[Win::Help] = newwin(1, max_width - (2 * BORDER_SIZE), max_height - 1, BORDER_SIZE); + mvwprintw(w[Win::Help], 0, 0, "Expand screen vertically to list available commands"); + } // set the title bar wbkgd(w[Win::Title], A_REVERSE); @@ -126,7 +131,7 @@ void ConsoleUI::initWindows() { // show windows on the real screen refresh(); displayTimelineDesc(); - displayHelp(); + if (max_height >= 23) displayHelp(); updateSummary(); updateTimeline(); for (auto win : w) { diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index c9ab7e7e2b..cc105dd10e 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -31,6 +31,8 @@ void Replay::setupServices(const std::vector &allow, const std::vec sockets_.resize(event_schema.getUnionFields().size(), nullptr); std::vector active_services; + active_services.reserve(services.size()); + for (const auto &[name, _] : services) { bool is_blocked = std::find(block.begin(), block.end(), name) != block.end(); bool is_allowed = allow.empty() || std::find(allow.begin(), allow.end(), name) != allow.end(); @@ -40,7 +42,9 @@ void Replay::setupServices(const std::vector &allow, const std::vec active_services.push_back(name.c_str()); } } - rInfo("active services: %s", join(active_services, ", ").c_str()); + + std::string services_str = join(active_services, ", "); + rInfo("active services: %s", services_str.c_str()); if (!sm_) { pm_ = std::make_unique(active_services); } @@ -59,7 +63,6 @@ void Replay::setupSegmentManager(bool has_filters) { } Replay::~Replay() { - seg_mgr_.reset(); if (stream_thread_.joinable()) { rInfo("shutdown: in progress..."); interruptStream([this]() { @@ -70,6 +73,7 @@ Replay::~Replay() { rInfo("shutdown: done"); } camera_server_.reset(); + seg_mgr_.reset(); } bool Replay::load() { diff --git a/tools/replay/seg_mgr.cc b/tools/replay/seg_mgr.cc index ee034fb083..f4e865d476 100644 --- a/tools/replay/seg_mgr.cc +++ b/tools/replay/seg_mgr.cc @@ -91,7 +91,8 @@ bool SegmentManager::mergeSegments(const SegmentMap::iterator &begin, const Segm auto &merged_events = merged_event_data->events; merged_events.reserve(total_event_count); - rDebug("merging segments: %s", join(segments_to_merge, ", ").c_str()); + std::string segments_str = join(segments_to_merge, ", "); + rDebug("merging segments: %s", segments_str.c_str()); for (int n : segments_to_merge) { const auto &events = segments_.at(n)->log->events; if (events.empty()) continue; diff --git a/tools/setup.sh b/tools/setup.sh index e0a9a4f6a6..fd7efcee90 100755 --- a/tools/setup.sh +++ b/tools/setup.sh @@ -1,6 +1,5 @@ #!/usr/bin/env bash - -set -e +set -euo pipefail RED='\033[0;31m' GREEN='\033[0;32m' diff --git a/uv.lock b/uv.lock index c34a6d9b71..b179517e0b 100644 --- a/uv.lock +++ b/uv.lock @@ -371,6 +371,41 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0c/58/bd257695f39d05594ca4ad60df5bcb7e32247f9951fd09a9b8edb82d1daa/contourpy-1.3.3-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:3d1a3799d62d45c18bafd41c5fa05120b96a28079f2393af559b843d1a966a77", size = 225315, upload-time = "2025-07-26T12:02:58.801Z" }, ] +[[package]] +name = "coverage" +version = "7.12.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/89/26/4a96807b193b011588099c3b5c89fbb05294e5b90e71018e065465f34eb6/coverage-7.12.0.tar.gz", hash = "sha256:fc11e0a4e372cb5f282f16ef90d4a585034050ccda536451901abfb19a57f40c", size = 819341, upload-time = "2025-11-18T13:34:20.766Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/5a/0c/0dfe7f0487477d96432e4815537263363fb6dd7289743a796e8e51eabdf2/coverage-7.12.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:aa124a3683d2af98bd9d9c2bfa7a5076ca7e5ab09fdb96b81fa7d89376ae928f", size = 217535, upload-time = "2025-11-18T13:32:08.812Z" }, + { url = "https://files.pythonhosted.org/packages/9b/f5/f9a4a053a5bbff023d3bec259faac8f11a1e5a6479c2ccf586f910d8dac7/coverage-7.12.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d93fbf446c31c0140208dcd07c5d882029832e8ed7891a39d6d44bd65f2316c3", size = 218044, upload-time = "2025-11-18T13:32:10.329Z" }, + { url = "https://files.pythonhosted.org/packages/95/c5/84fc3697c1fa10cd8571919bf9693f693b7373278daaf3b73e328d502bc8/coverage-7.12.0-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:52ca620260bd8cd6027317bdd8b8ba929be1d741764ee765b42c4d79a408601e", size = 248440, upload-time = "2025-11-18T13:32:12.536Z" }, + { url = "https://files.pythonhosted.org/packages/f4/36/2d93fbf6a04670f3874aed397d5a5371948a076e3249244a9e84fb0e02d6/coverage-7.12.0-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:f3433ffd541380f3a0e423cff0f4926d55b0cc8c1d160fdc3be24a4c03aa65f7", size = 250361, upload-time = "2025-11-18T13:32:13.852Z" }, + { url = "https://files.pythonhosted.org/packages/5d/49/66dc65cc456a6bfc41ea3d0758c4afeaa4068a2b2931bf83be6894cf1058/coverage-7.12.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f7bbb321d4adc9f65e402c677cd1c8e4c2d0105d3ce285b51b4d87f1d5db5245", size = 252472, upload-time = "2025-11-18T13:32:15.068Z" }, + { url = "https://files.pythonhosted.org/packages/35/1f/ebb8a18dffd406db9fcd4b3ae42254aedcaf612470e8712f12041325930f/coverage-7.12.0-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:22a7aade354a72dff3b59c577bfd18d6945c61f97393bc5fb7bd293a4237024b", size = 248592, upload-time = "2025-11-18T13:32:16.328Z" }, + { url = "https://files.pythonhosted.org/packages/da/a8/67f213c06e5ea3b3d4980df7dc344d7fea88240b5fe878a5dcbdfe0e2315/coverage-7.12.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:3ff651dcd36d2fea66877cd4a82de478004c59b849945446acb5baf9379a1b64", size = 250167, upload-time = "2025-11-18T13:32:17.687Z" }, + { url = "https://files.pythonhosted.org/packages/f0/00/e52aef68154164ea40cc8389c120c314c747fe63a04b013a5782e989b77f/coverage-7.12.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:31b8b2e38391a56e3cea39d22a23faaa7c3fc911751756ef6d2621d2a9daf742", size = 248238, upload-time = "2025-11-18T13:32:19.2Z" }, + { url = "https://files.pythonhosted.org/packages/1f/a4/4d88750bcf9d6d66f77865e5a05a20e14db44074c25fd22519777cb69025/coverage-7.12.0-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:297bc2da28440f5ae51c845a47c8175a4db0553a53827886e4fb25c66633000c", size = 247964, upload-time = "2025-11-18T13:32:21.027Z" }, + { url = "https://files.pythonhosted.org/packages/a7/6b/b74693158899d5b47b0bf6238d2c6722e20ba749f86b74454fac0696bb00/coverage-7.12.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6ff7651cc01a246908eac162a6a86fc0dbab6de1ad165dfb9a1e2ec660b44984", size = 248862, upload-time = "2025-11-18T13:32:22.304Z" }, + { url = "https://files.pythonhosted.org/packages/18/de/6af6730227ce0e8ade307b1cc4a08e7f51b419a78d02083a86c04ccceb29/coverage-7.12.0-cp311-cp311-win32.whl", hash = "sha256:313672140638b6ddb2c6455ddeda41c6a0b208298034544cfca138978c6baed6", size = 220033, upload-time = "2025-11-18T13:32:23.714Z" }, + { url = "https://files.pythonhosted.org/packages/e2/a1/e7f63021a7c4fe20994359fcdeae43cbef4a4d0ca36a5a1639feeea5d9e1/coverage-7.12.0-cp311-cp311-win_amd64.whl", hash = "sha256:a1783ed5bd0d5938d4435014626568dc7f93e3cb99bc59188cc18857c47aa3c4", size = 220966, upload-time = "2025-11-18T13:32:25.599Z" }, + { url = "https://files.pythonhosted.org/packages/77/e8/deae26453f37c20c3aa0c4433a1e32cdc169bf415cce223a693117aa3ddd/coverage-7.12.0-cp311-cp311-win_arm64.whl", hash = "sha256:4648158fd8dd9381b5847622df1c90ff314efbfc1df4550092ab6013c238a5fc", size = 219637, upload-time = "2025-11-18T13:32:27.265Z" }, + { url = "https://files.pythonhosted.org/packages/02/bf/638c0427c0f0d47638242e2438127f3c8ee3cfc06c7fdeb16778ed47f836/coverage-7.12.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:29644c928772c78512b48e14156b81255000dcfd4817574ff69def189bcb3647", size = 217704, upload-time = "2025-11-18T13:32:28.906Z" }, + { url = "https://files.pythonhosted.org/packages/08/e1/706fae6692a66c2d6b871a608bbde0da6281903fa0e9f53a39ed441da36a/coverage-7.12.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8638cbb002eaa5d7c8d04da667813ce1067080b9a91099801a0053086e52b736", size = 218064, upload-time = "2025-11-18T13:32:30.161Z" }, + { url = "https://files.pythonhosted.org/packages/a9/8b/eb0231d0540f8af3ffda39720ff43cb91926489d01524e68f60e961366e4/coverage-7.12.0-cp312-cp312-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:083631eeff5eb9992c923e14b810a179798bb598e6a0dd60586819fc23be6e60", size = 249560, upload-time = "2025-11-18T13:32:31.835Z" }, + { url = "https://files.pythonhosted.org/packages/e9/a1/67fb52af642e974d159b5b379e4d4c59d0ebe1288677fbd04bbffe665a82/coverage-7.12.0-cp312-cp312-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:99d5415c73ca12d558e07776bd957c4222c687b9f1d26fa0e1b57e3598bdcde8", size = 252318, upload-time = "2025-11-18T13:32:33.178Z" }, + { url = "https://files.pythonhosted.org/packages/41/e5/38228f31b2c7665ebf9bdfdddd7a184d56450755c7e43ac721c11a4b8dab/coverage-7.12.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e949ebf60c717c3df63adb4a1a366c096c8d7fd8472608cd09359e1bd48ef59f", size = 253403, upload-time = "2025-11-18T13:32:34.45Z" }, + { url = "https://files.pythonhosted.org/packages/ec/4b/df78e4c8188f9960684267c5a4897836f3f0f20a20c51606ee778a1d9749/coverage-7.12.0-cp312-cp312-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:6d907ddccbca819afa2cd014bc69983b146cca2735a0b1e6259b2a6c10be1e70", size = 249984, upload-time = "2025-11-18T13:32:35.747Z" }, + { url = "https://files.pythonhosted.org/packages/ba/51/bb163933d195a345c6f63eab9e55743413d064c291b6220df754075c2769/coverage-7.12.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:b1518ecbad4e6173f4c6e6c4a46e49555ea5679bf3feda5edb1b935c7c44e8a0", size = 251339, upload-time = "2025-11-18T13:32:37.352Z" }, + { url = "https://files.pythonhosted.org/packages/15/40/c9b29cdb8412c837cdcbc2cfa054547dd83affe6cbbd4ce4fdb92b6ba7d1/coverage-7.12.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:51777647a749abdf6f6fd8c7cffab12de68ab93aab15efc72fbbb83036c2a068", size = 249489, upload-time = "2025-11-18T13:32:39.212Z" }, + { url = "https://files.pythonhosted.org/packages/c8/da/b3131e20ba07a0de4437a50ef3b47840dfabf9293675b0cd5c2c7f66dd61/coverage-7.12.0-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:42435d46d6461a3b305cdfcad7cdd3248787771f53fe18305548cba474e6523b", size = 249070, upload-time = "2025-11-18T13:32:40.598Z" }, + { url = "https://files.pythonhosted.org/packages/70/81/b653329b5f6302c08d683ceff6785bc60a34be9ae92a5c7b63ee7ee7acec/coverage-7.12.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:5bcead88c8423e1855e64b8057d0544e33e4080b95b240c2a355334bb7ced937", size = 250929, upload-time = "2025-11-18T13:32:42.915Z" }, + { url = "https://files.pythonhosted.org/packages/a3/00/250ac3bca9f252a5fb1338b5ad01331ebb7b40223f72bef5b1b2cb03aa64/coverage-7.12.0-cp312-cp312-win32.whl", hash = "sha256:dcbb630ab034e86d2a0f79aefd2be07e583202f41e037602d438c80044957baa", size = 220241, upload-time = "2025-11-18T13:32:44.665Z" }, + { url = "https://files.pythonhosted.org/packages/64/1c/77e79e76d37ce83302f6c21980b45e09f8aa4551965213a10e62d71ce0ab/coverage-7.12.0-cp312-cp312-win_amd64.whl", hash = "sha256:2fd8354ed5d69775ac42986a691fbf68b4084278710cee9d7c3eaa0c28fa982a", size = 221051, upload-time = "2025-11-18T13:32:46.008Z" }, + { url = "https://files.pythonhosted.org/packages/31/f5/641b8a25baae564f9e52cac0e2667b123de961985709a004e287ee7663cc/coverage-7.12.0-cp312-cp312-win_arm64.whl", hash = "sha256:737c3814903be30695b2de20d22bcc5428fdae305c61ba44cdc8b3252984c49c", size = 219692, upload-time = "2025-11-18T13:32:47.372Z" }, + { url = "https://files.pythonhosted.org/packages/ce/a3/43b749004e3c09452e39bb56347a008f0a0668aad37324a99b5c8ca91d9e/coverage-7.12.0-py3-none-any.whl", hash = "sha256:159d50c0b12e060b15ed3d39f87ed43d4f7f7ad40b8a534f4dd331adbb51104a", size = 209503, upload-time = "2025-11-18T13:34:18.892Z" }, +] + [[package]] name = "crcmod" version = "1.7" @@ -1349,6 +1384,7 @@ docs = [ ] testing = [ { name = "codespell" }, + { name = "coverage" }, { name = "hypothesis" }, { name = "mypy" }, { name = "pre-commit-hooks" }, @@ -1364,7 +1400,7 @@ testing = [ { name = "ruff" }, ] tools = [ - { name = "dearpygui" }, + { name = "dearpygui", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, { name = "metadrive-simulator", marker = "platform_machine != 'aarch64'" }, ] @@ -1378,10 +1414,11 @@ requires-dist = [ { name = "casadi", specifier = ">=3.6.6" }, { name = "cffi" }, { name = "codespell", marker = "extra == 'testing'" }, + { name = "coverage", marker = "extra == 'testing'" }, { name = "crcmod" }, { name = "cython" }, { name = "dbus-next", marker = "extra == 'dev'" }, - { name = "dearpygui", marker = "extra == 'tools'", specifier = ">=2.1.0" }, + { name = "dearpygui", marker = "(platform_machine != 'aarch64' and extra == 'tools') or (sys_platform != 'linux' and extra == 'tools')", specifier = ">=2.1.0" }, { name = "dictdiffer", marker = "extra == 'dev'" }, { name = "future-fstrings" }, { name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" }, @@ -1422,7 +1459,7 @@ requires-dist = [ { name = "pytest-subtests", marker = "extra == 'testing'" }, { name = "pytest-timeout", marker = "extra == 'testing'" }, { name = "pytest-xdist", marker = "extra == 'testing'", git = "https://github.com/sshane/pytest-xdist?rev=2b4372bd62699fb412c4fe2f95bf9f01bd2018da" }, - { name = "pytools", marker = "platform_machine != 'aarch64' and extra == 'dev'", specifier = "<2024.1.11" }, + { name = "pytools", marker = "platform_machine != 'aarch64' and extra == 'dev'", specifier = ">=2025.1.6" }, { name = "pywinctl", marker = "extra == 'dev'" }, { name = "pyzmq" }, { name = "qrcode" }, @@ -4451,16 +4488,16 @@ sdist = { url = "https://files.pythonhosted.org/packages/ef/c6/2c5999de3bb153352 [[package]] name = "pytools" -version = "2024.1.10" +version = "2025.2.5" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "platformdirs", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, { name = "siphash24", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, { name = "typing-extensions", marker = "platform_machine != 'aarch64' or sys_platform != 'linux'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ee/0f/56e109c0307f831b5d598ad73976aaaa84b4d0e98da29a642e797eaa940c/pytools-2024.1.10.tar.gz", hash = "sha256:9af6f4b045212c49be32bb31fe19606c478ee4b09631886d05a32459f4ce0a12", size = 81741, upload-time = "2024-07-17T18:47:38.287Z" } +sdist = { url = "https://files.pythonhosted.org/packages/c3/7b/f885a57e61ded45b5b10ca60f0b7575c9fb9a282e7513d0e23a33ee647e1/pytools-2025.2.5.tar.gz", hash = "sha256:a7f5350644d46d98ee9c7e67b4b41693308aa0f5e9b188d8f0694b27dc94e3a2", size = 85594, upload-time = "2025-10-07T15:53:30.49Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/66/cf/0a6aaa44b1f9e02b8c0648b5665a82246a93bcc75224c167b4fafa25c093/pytools-2024.1.10-py3-none-any.whl", hash = "sha256:9cabb71038048291400e244e2da441a051d86053339bc484e64e58d8ea263f44", size = 88108, upload-time = "2024-07-17T18:47:36.173Z" }, + { url = "https://files.pythonhosted.org/packages/f6/84/c42c29ca4bff35baa286df70b0097e0b1c88fd57e8e6bdb09cb161a6f3c1/pytools-2025.2.5-py3-none-any.whl", hash = "sha256:42e93751ec425781e103bbcd769ba35ecbacd43339c2905401608f2fdc30cf19", size = 98811, upload-time = "2025-10-07T15:53:29.089Z" }, ] [[package]]