diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml index 34e333bb59..c86c044772 100644 --- a/.github/workflows/release.yaml +++ b/.github/workflows/release.yaml @@ -1,7 +1,7 @@ name: release on: schedule: - - cron: '0 10 * * *' + - cron: '0 9 * * *' workflow_dispatch: jobs: diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 6e17f5a480..e6b5950cbb 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -41,7 +41,12 @@ jobs: - uses: actions/checkout@v4 with: submodules: true - - run: git lfs pull + - name: Getting LFS files + uses: nick-fields/retry@7152eba30c6575329ac0576536151aca5a72780e + with: + timeout_minutes: 2 + max_attempts: 3 + command: git lfs pull - name: Build devel timeout-minutes: 1 run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh @@ -97,26 +102,26 @@ jobs: build_mac: name: build macOS - runs-on: macos-latest + runs-on: namespace-profile-macos-8x14 steps: - uses: actions/checkout@v4 with: submodules: true - - run: git lfs pull + - name: Homebrew cache + uses: ./.github/workflows/auto-cache + with: + path: ~/Library/Caches/Homebrew - name: Install dependencies run: ./tools/mac_setup.sh env: # package install has DeprecationWarnings PYTHONWARNINGS: default + - run: git lfs pull - run: echo "CACHE_COMMIT_DATE=$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d-%H:%M')" >> $GITHUB_ENV - name: Getting scons cache - uses: 'actions/cache@v4' + uses: ./.github/workflows/auto-cache with: path: /tmp/scons_cache - key: scons-${{ runner.arch }}-macos-${{ env.CACHE_COMMIT_DATE }}-${{ github.sha }} - restore-keys: | - scons-${{ runner.arch }}-macos-${{ env.CACHE_COMMIT_DATE }} - scons-${{ runner.arch }}-macos - name: Building openpilot run: . .venv/bin/activate && scons -j$(nproc) @@ -169,10 +174,10 @@ jobs: timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 10 || 30) }} # allow more time when we missed the scons cache run: ${{ env.RUN }} "scons -j$(nproc)" - name: Run unit tests - timeout-minutes: 15 + timeout-minutes: 1 run: | ${{ env.RUN }} "source selfdrive/test/setup_xvfb.sh && \ - $PYTEST --timeout 60 -m 'not slow' && \ + MAX_EXAMPLES=1 $PYTEST --timeout 60 -m 'not slow' && \ ./selfdrive/ui/tests/create_test_translations.sh && \ QT_QPA_PLATFORM=offscreen ./selfdrive/ui/tests/test_translations && \ pytest ./selfdrive/ui/tests/test_translations.py" @@ -246,7 +251,7 @@ jobs: strategy: fail-fast: false matrix: - job: [0, 1] + job: [0, 1, 2, 3] steps: - uses: actions/checkout@v4 with: @@ -261,12 +266,12 @@ jobs: - name: Build openpilot run: ${{ env.RUN }} "scons -j$(nproc)" - name: Test car models - timeout-minutes: 20 + timeout-minutes: 2 run: | - ${{ env.RUN }} "$PYTEST selfdrive/car/tests/test_models.py && \ + ${{ env.RUN }} "FILEREADER_CACHE=1 MAX_EXAMPLES=1 $PYTEST selfdrive/car/tests/test_models.py && \ chmod -R 777 /tmp/comma_download_cache" env: - NUM_JOBS: 2 + NUM_JOBS: 4 JOB_ID: ${{ matrix.job }} - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v4 diff --git a/.github/workflows/setup/action.yaml b/.github/workflows/setup/action.yaml index 701675942f..1315ba989e 100644 --- a/.github/workflows/setup/action.yaml +++ b/.github/workflows/setup/action.yaml @@ -20,6 +20,18 @@ runs: echo "You should not run this action directly. Use setup-with-retry instead" exit 1 + - shell: bash + name: No retries! + run: | + if [ "${{ github.run_attempt }}" -gt 1 ]; then + echo -e "\033[31m" + echo "##################################################" + echo " Retries not allowed! Fix the flaky test! " + echo "##################################################" + echo -e "\033[0m" + exit 1 + fi + # do this after checkout to ensure our custom LFS config is used to pull from GitLab - shell: bash run: git lfs pull diff --git a/.gitignore b/.gitignore index 919e011fe3..4562e47817 100644 --- a/.gitignore +++ b/.gitignore @@ -76,6 +76,7 @@ selfdrive/modeld/models/*.thneed selfdrive/modeld/models/*.pkl *.bz2 +*.zst build/ diff --git a/Jenkinsfile b/Jenkinsfile index b47a3884a0..7a392cdd2b 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -66,7 +66,7 @@ fi ln -snf ${env.TEST_DIR} /data/pythonpath cd ${env.TEST_DIR} || true -${cmd} +time ${cmd} END""" sh script: ssh_cmd, label: step_label @@ -198,7 +198,7 @@ node { //["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR $SOURCE_DIR/scripts/retry.sh ./build_devel.sh"], step("build openpilot", "cd system/manager && ./build.py"), step("check dirty", "release/check-dirty.sh"), - step("onroad tests", "pytest selfdrive/test/test_onroad.py -s"), + step("onroad tests", "pytest selfdrive/test/test_onroad.py -s", [timeout: 60]), //["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], ]) }, @@ -207,7 +207,7 @@ node { step("build", "cd system/manager && ./build.py"), step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda/", "selfdrive/pandad/"]]), step("test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"), - step("test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py"), + step("test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py", [timeout: 60]), step("test pigeond", "pytest system/ubloxd/tests/test_pigeond.py"), step("test manager", "pytest system/manager/test/test_manager.py"), ]) @@ -221,12 +221,12 @@ node { 'camerad': { deviceStage("AR0231", "tici-ar0231", ["UNSAFE=1"], [ step("build", "cd system/manager && ./build.py"), - step("test camerad", "pytest system/camerad/test/test_camerad.py"), + step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), step("test exposure", "pytest system/camerad/test/test_exposure.py"), ]) deviceStage("OX03C10", "tici-ox03c10", ["UNSAFE=1"], [ step("build", "cd system/manager && ./build.py"), - step("test camerad", "pytest system/camerad/test/test_camerad.py"), + step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), step("test exposure", "pytest system/camerad/test/test_exposure.py"), ]) }, diff --git a/RELEASES.md b/RELEASES.md index 1435809d84..dbec5206cc 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -4,8 +4,12 @@ Version 0.9.8 (2024-XX-XX) * Trained in brand new ML simulator * Model now gates applying positive accel in Chill mode * New driving monitoring model - * Reduced false positives related to passengers + * Reduced false positives related to passengers +* Image processing pipeline moved to the ISP + * More GPU time for driving models + * Power draw reduced 0.5W, which means your device runs cooler * Added toggle to enable driver monitoring even when openpilot is not engaged +* Enable openpilot longitudinal control for Ford Q3 vehicles * New Toyota TSS2 longitudinal tune Version 0.9.7 (2024-06-13) diff --git a/cereal/messaging/tests/test_pub_sub_master.py b/cereal/messaging/tests/test_pub_sub_master.py index 99965319eb..e9bc7a85cb 100644 --- a/cereal/messaging/tests/test_pub_sub_master.py +++ b/cereal/messaging/tests/test_pub_sub_master.py @@ -63,14 +63,13 @@ class TestSubMaster: def test_update_timeout(self): sock = random_sock() sm = messaging.SubMaster([sock,]) - for _ in range(5): - timeout = random.randrange(1000, 5000) - start_time = time.monotonic() - sm.update(timeout) - t = time.monotonic() - start_time - assert t >= timeout/1000. - assert t < 5 - assert not any(sm.updated.values()) + timeout = random.randrange(1000, 3000) + start_time = time.monotonic() + sm.update(timeout) + t = time.monotonic() - start_time + assert t >= timeout/1000. + assert t < 3 + assert not any(sm.updated.values()) def test_avg_frequency_checks(self): for poll in (True, False): diff --git a/common/pid.py b/common/pid.py index 29c4d8bd46..36cbf9c4e9 100644 --- a/common/pid.py +++ b/common/pid.py @@ -59,15 +59,13 @@ class PIDController: if override: self.i -= self.i_unwind_rate * float(np.sign(self.i)) else: - i = self.i + error * self.k_i * self.i_rate - control = self.p + i + self.d + self.f - - # Update when changing i will move the control away from the limits - # or when i will move towards the sign of the error - if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or - (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ - not freeze_integrator: - self.i = i + if not freeze_integrator: + self.i = self.i + error * self.k_i * self.i_rate + + # Clip i to prevent exceeding control limits + control_no_i = self.p + self.d + self.f + control_no_i = clip(control_no_i, self.neg_limit, self.pos_limit) + self.i = clip(self.i, self.neg_limit - control_no_i, self.pos_limit - control_no_i) control = self.p + self.i + self.d + self.f diff --git a/docs/CARS.md b/docs/CARS.md index 44c9327378..6861f411d2 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -30,21 +30,21 @@ A supported vehicle is one that just works when you install a comma device. All |comma|body|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None|| |CUPRA|Ateca 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Dodge|Durango 2020-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Bronco Sport 2021-24|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Escape 2020-22|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Escape Hybrid 2020-22|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Explorer 2020-23|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Explorer Hybrid 2020-23|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Focus 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Focus Hybrid 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Kuga 2020-22|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Kuga Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Kuga Plug-in Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick 2022|LARIAT Luxury|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick 2023-24|Co-Pilot360 Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick Hybrid 2022|LARIAT Luxury|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Maverick Hybrid 2023-24|Co-Pilot360 Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Bronco Sport 2021-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Escape 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Escape Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Explorer 2020-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Explorer Hybrid 2020-24|Co-Pilot360 Assist+|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Focus 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Focus Hybrid 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Kuga 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Kuga Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Kuga Plug-in Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Maverick 2022|LARIAT Luxury|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Maverick 2023-24|Co-Pilot360 Assist|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Maverick Hybrid 2022|LARIAT Luxury|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Maverick Hybrid 2023-24|Co-Pilot360 Assist|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G70 2018|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G70 2019-21|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G70 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -184,8 +184,8 @@ A supported vehicle is one that just works when you install a comma device. All |Lexus|RX Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|RX Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|UX Hybrid 2019-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lincoln|Aviator 2020-24|Co-Pilot360 Plus|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lincoln|Aviator Plug-in Hybrid 2020-24|Co-Pilot360 Plus|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lincoln|Aviator 2020-24|Co-Pilot360 Plus|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lincoln|Aviator Plug-in Hybrid 2020-24|Co-Pilot360 Plus|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |MAN|eTGE 2020-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |MAN|TGE 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Mazda|CX-5 2022-24|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| diff --git a/docs/how-to/connect-to-comma.md b/docs/how-to/connect-to-comma.md index 67327fbaaf..5797f8618f 100644 --- a/docs/how-to/connect-to-comma.md +++ b/docs/how-to/connect-to-comma.md @@ -11,6 +11,9 @@ On the comma three, the serial console is exposed through a UART-to-USB chip, an On the comma 3X, the serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script. + * Username: `comma` + * Password: `comma` + ## SSH In order to SSH into your device, you'll need a GitHub account with SSH keys. See this [GitHub article](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh) for getting your account setup with SSH keys. diff --git a/opendbc_repo b/opendbc_repo index d632cc5bec..9b5f697a1e 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit d632cc5bec14d4e077fdf25e19b24b434c2653fd +Subproject commit 9b5f697a1ec82cf3a27ac0c93367ff91e83bedb2 diff --git a/panda b/panda index 0b364ece1e..aab03bc4b6 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 0b364ece1eafa2e66b71be7cade3fdfb56a3014e +Subproject commit aab03bc4b6ab02be7db3fd60f034a84d79ad93b4 diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 2a62127749..b50955b2a9 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -4,6 +4,7 @@ import pytest import random import unittest # noqa: TID251 from collections import defaultdict, Counter +from functools import partial import hypothesis.strategies as st from hypothesis import Phase, given, settings from parameterized import parameterized_class @@ -22,7 +23,8 @@ from openpilot.selfdrive.selfdrived.selfdrived import SelfdriveD from openpilot.selfdrive.pandad import can_capnp_to_list from openpilot.selfdrive.test.helpers import read_segment_list from openpilot.system.hardware.hw import DEFAULT_DOWNLOAD_CACHE_ROOT -from openpilot.tools.lib.logreader import LogReader, LogsUnavailable +from openpilot.tools.lib.logreader import LogReader, LogsUnavailable, openpilotci_source_zst, openpilotci_source, internal_source, \ + internal_source_zst, comma_api_source, auto_source from openpilot.tools.lib.route import SegmentName from panda.tests.libpanda import libpanda_py @@ -93,7 +95,7 @@ class TestCarModelBase(unittest.TestCase): car_fw = msg.carParams.carFw if msg.carParams.openpilotLongitudinalControl: experimental_long = True - if cls.platform is None and not cls.test_route_on_bucket: + if cls.platform is None: live_fingerprint = msg.carParams.carFingerprint cls.platform = MIGRATION.get(live_fingerprint, live_fingerprint) @@ -126,7 +128,9 @@ class TestCarModelBase(unittest.TestCase): segment_range = f"{cls.test_route.route}/{seg}" try: - lr = LogReader(segment_range) + source = partial(auto_source, sources=[internal_source, internal_source_zst] if len(INTERNAL_SEG_LIST) else \ + [openpilotci_source_zst, openpilotci_source, comma_api_source]) + lr = LogReader(segment_range, source=source) return cls.get_testing_data_from_logreader(lr) except (LogsUnavailable, AssertionError): pass diff --git a/selfdrive/debug/check_can_parser_performance.py b/selfdrive/debug/check_can_parser_performance.py index 2bddd362ae..7a0db1926b 100755 --- a/selfdrive/debug/check_can_parser_performance.py +++ b/selfdrive/debug/check_can_parser_performance.py @@ -14,7 +14,6 @@ N_RUNS = 10 class CarModelTestCase(TestCarModelBase): test_route = CarTestRoute(DEMO_ROUTE, None) - ci = False if __name__ == '__main__': diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index 3030b31a0c..31440c1295 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -139,7 +139,6 @@ def main(): pm = PubMaster(["driverStateV2"]) calib = np.zeros(CALIB_LEN, dtype=np.float32) - # last = 0 while True: buf = vipc_client.recv() @@ -155,8 +154,6 @@ def main(): t2 = time.perf_counter() pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, gpu_execution_time)) - # print("dmonitoring process: %.2fms, from last %.2fms\n" % (t2 - t1, t1 - last)) - # last = t1 if __name__ == "__main__": diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 5ec978e566..2a0ddef57b 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:2a845fd16d6482222c574db833d2badb37ebcdf9c7d2987ab347ef63e728a146 -size 50309976 +oid sha256:c829d824ebc73d15da82516592c07d9784369ccbf710698e919e06a702e70924 +size 50320138 diff --git a/selfdrive/pandad/pandad.cc b/selfdrive/pandad/pandad.cc index b0b10fe315..a85159f33a 100644 --- a/selfdrive/pandad/pandad.cc +++ b/selfdrive/pandad/pandad.cc @@ -306,6 +306,16 @@ void send_peripheral_state(Panda *panda, PubMaster *pm) { LOGW("reading hwmon took %lfms", read_time); } + // fall back to panda's voltage and current measurement + if (ps.getVoltage() == 0 && ps.getCurrent() == 0) { + auto health_opt = panda->get_state(); + if (health_opt) { + health_t health = *health_opt; + ps.setVoltage(health.voltage_pkt); + ps.setCurrent(health.current_pkt); + } + } + uint16_t fan_speed_rpm = panda->get_fan_speed(); ps.setFanSpeedRpm(fan_speed_rpm); diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index cb3db26344..5376f91aee 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -6,6 +6,7 @@ import capnp from cereal import messaging, car, log from opendbc.car.fingerprints import MIGRATION from opendbc.car.toyota.values import EPS_SCALE +from opendbc.car.ford.values import CAR as FORD, FordFlags from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index @@ -270,6 +271,8 @@ def migrate_pandaStates(msgs): "TOYOTA_RAV4": EPS_SCALE["TOYOTA_RAV4"] | Panda.FLAG_TOYOTA_ALT_BRAKE, "KIA_EV6": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CANFD_HDA2, } + # TODO: get new Ford route + safety_param_migration |= {car: Panda.FLAG_FORD_LONG_CONTROL for car in (set(FORD) - FORD.with_flags(FordFlags.CANFD))} # Migrate safety param base on carParams CP = next((m.carParams for _, m in msgs if m.which() == 'carParams'), None) diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 7ffaea76b4..c6720cc601 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -58,10 +58,18 @@ def generate_report(proposed, master, tmp, commit): (lambda x: x.laneLines[1].y[0], "laneLines.y"), (lambda x: x.meta.disengagePredictions.gasPressProbs[1], "gasPressProbs") ], "modelV2") + DriverStateV2_Plots = zl([ + (lambda x: x.wheelOnRightProb, "wheelOnRightProb"), + (lambda x: x.leftDriverData.faceProb, "leftDriverData.faceProb"), + (lambda x: x.leftDriverData.faceOrientation[0], "leftDriverData.faceOrientation0"), + (lambda x: x.leftDriverData.leftBlinkProb, "leftDriverData.leftBlinkProb"), + (lambda x: x.leftDriverData.notReadyProb[0], "leftDriverData.notReadyProb0"), + (lambda x: x.rightDriverData.faceProb, "rightDriverData.faceProb"), + ], "driverStateV2") return [plot(map(v[0], get_event(proposed, event)), \ map(v[0], get_event(master, event)), f"{v[1]}_{commit[:7]}", tmp) \ - for v,event in [*ModelV2_Plots]] + for v,event in ([*ModelV2_Plots] + [*DriverStateV2_Plots])] def create_table(title, files, link, open_table=False): if not files: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 2f565836fd..c779902d6b 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -992ac80ef848afb85562ca24b1c5a3d410aacd05 \ No newline at end of file +2fc2e865ab77fd8145feab86d454f2111c5d9871 diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index ec84f37d1f..4f0705f492 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -56,7 +56,7 @@ segments = [ ("NISSAN", "regen58464878D07|2024-08-30--03-15-31--0"), ("VOLKSWAGEN", "regenED976DEB757|2024-08-30--03-18-02--0"), ("MAZDA", "regenACF84CCF482|2024-08-30--03-21-55--0"), - ("FORD", "regen6ECC59A6307|2024-08-30--03-25-42--0"), + ("FORD", "regen756F8230C21|2024-11-07--00-08-24--0"), ] # dashcamOnly makes don't need to be tested until a full port is done diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 35338419de..6167e12999 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -10,8 +10,8 @@ import time import numpy as np import zstandard as zstd from collections import Counter, defaultdict -from functools import cached_property from pathlib import Path +from tabulate import tabulate from cereal import car, log import cereal.messaging as messaging @@ -33,6 +33,9 @@ CPU usage budget should not exceed MAX_TOTAL_CPU """ +TEST_DURATION = 25 +LOG_OFFSET = 8 + MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process @@ -49,28 +52,28 @@ PROCS = { "selfdrive.controls.radard": 2.0, "selfdrive.modeld.modeld": 17.0, "selfdrive.modeld.dmonitoringmodeld": 11.0, - "system.hardware.hardwared": 3.87, + "system.hardware.hardwared": 4.0, "selfdrive.locationd.calibrationd": 2.0, "selfdrive.locationd.torqued": 5.0, "selfdrive.locationd.locationd": 25.0, "selfdrive.ui.soundd": 3.0, "selfdrive.monitoring.dmonitoringd": 4.0, - "./proclogd": 1.54, - "system.logmessaged": 0.2, + "./proclogd": 2.0, + "system.logmessaged": 1.0, "system.tombstoned": 0, - "./logcatd": 0, + "./logcatd": 1.0, "system.micd": 5.0, "system.timed": 0, "selfdrive.pandad.pandad": 0, - "system.statsd": 0.4, - "system.loggerd.uploader": (0.5, 15.0), - "system.loggerd.deleter": 0.1, + "system.statsd": 1.0, + "system.loggerd.uploader": 15.0, + "system.loggerd.deleter": 1.0, } PROCS.update({ "tici": { "./pandad": 4.0, - "./ubloxd": 0.02, + "./ubloxd": 1.0, "system.ubloxd.pigeond": 6.0, }, "tizi": { @@ -98,6 +101,13 @@ TIMINGS = { "wideRoadCameraState": [1.5, 0.35], } +LOGS_SIZE_RATE = { + "qlog": 0.0083, + "rlog": 0.1528, + "qcamera.ts": 0.03828, +} +LOGS_SIZE_RATE.update(dict.fromkeys(['ecamera.hevc', 'fcamera.hevc'], 1.2740)) + def cputime_total(ct): return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem @@ -124,7 +134,7 @@ class TestOnroad: if os.path.exists(Paths.log_root()): shutil.rmtree(Paths.log_root()) - # start manager and run openpilot for a minute + # start manager and run openpilot for TEST_DURATION proc = None try: manager_path = os.path.join(BASEDIR, "system/manager/manager.py") @@ -135,26 +145,24 @@ class TestOnroad: while sm.recv_frame['carState'] < 0: sm.update(1000) - # make sure we get at least two full segments route = None cls.segments = [] with Timeout(300, "timed out waiting for logs"): while route is None: route = params.get("CurrentRoute", encoding="utf-8") - time.sleep(0.1) + time.sleep(0.01) # test car params caching params.put("CarParamsCache", car.CarParams().to_bytes()) - while len(cls.segments) < 3: + while len(cls.segments) < 1: segs = set() if Path(Paths.log_root()).exists(): segs = set(Path(Paths.log_root()).glob(f"{route}--*")) cls.segments = sorted(segs, key=lambda s: int(str(s).rsplit('--')[-1])) - time.sleep(2) + time.sleep(0.01) - # chop off last, incomplete segment - cls.segments = cls.segments[:-1] + time.sleep(TEST_DURATION) finally: cls.gpu_procs = {psutil.Process(int(f.name)).name() for f in pathlib.Path('/sys/devices/virtual/kgsl/kgsl/proc/').iterdir() if f.is_dir()} @@ -166,9 +174,8 @@ class TestOnroad: cls.lrs = [list(LogReader(os.path.join(str(s), "rlog"))) for s in cls.segments] - # use the second segment by default as it's the first full segment - cls.lr = list(LogReader(os.path.join(str(cls.segments[1]), "rlog"))) - cls.log_path = cls.segments[1] + cls.lr = list(LogReader(os.path.join(str(cls.segments[0]), "rlog"))) + cls.log_path = cls.segments[0] cls.log_sizes = {} for f in cls.log_path.iterdir(): @@ -178,16 +185,13 @@ class TestOnroad: with open(f, 'rb') as ff: cls.log_sizes[f] = len(zstd.compress(ff.read(), LOG_COMPRESSION_LEVEL)) / 1e6 + cls.msgs = defaultdict(list) + for m in cls.lr: + cls.msgs[m.which()].append(m) - @cached_property - def service_msgs(self): - msgs = defaultdict(list) - for m in self.lr: - msgs[m.which()].append(m) - return msgs def test_service_frequencies(self, subtests): - for s, msgs in self.service_msgs.items(): + for s, msgs in self.msgs.items(): if s in ('initData', 'sentinel'): continue @@ -196,10 +200,10 @@ class TestOnroad: continue with subtests.test(service=s): - assert len(msgs) >= math.floor(SERVICE_LIST[s].frequency*55) + assert len(msgs) >= math.floor(SERVICE_LIST[s].frequency*int(TEST_DURATION*0.8)) def test_cloudlog_size(self): - msgs = [m for m in self.lr if m.which() == 'logMessage'] + msgs = self.msgs['logMessage'] total_size = sum(len(m.as_builder().to_bytes()) for m in msgs) assert total_size < 3.5e5 @@ -210,16 +214,10 @@ class TestOnroad: def test_log_sizes(self): for f, sz in self.log_sizes.items(): - if f.name == "qcamera.ts": - assert 2.15 < sz < 2.6 - elif f.name == "qlog": - assert 0.4 < sz < 0.55 - elif f.name == "rlog": - assert 5 < sz < 50 - elif f.name.endswith('.hevc'): - assert 70 < sz < 80 - else: - raise NotImplementedError + rate = LOGS_SIZE_RATE[f.name] + minn = rate * TEST_DURATION * 0.8 + maxx = rate * TEST_DURATION * 1.2 + assert minn < sz < maxx def test_ui_timings(self): result = "\n" @@ -227,7 +225,7 @@ class TestOnroad: result += "-------------- UI Draw Timing ------------------\n" result += "------------------------------------------------\n" - ts = [m.uiDebug.drawTimeMillis for m in self.service_msgs['uiDebug']] + ts = [m.uiDebug.drawTimeMillis for m in self.msgs['uiDebug']] 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" @@ -244,53 +242,44 @@ class TestOnroad: assert len(veryslow) < 5, f"Too many slow frame draw times: {veryslow}" def test_cpu_usage(self, subtests): - result = "\n" - result += "------------------------------------------------\n" - result += "------------------ CPU Usage -------------------\n" - result += "------------------------------------------------\n" + print("\n------------------------------------------------") + print("------------------ CPU Usage -------------------") + print("------------------------------------------------") plogs_by_proc = defaultdict(list) - for pl in self.service_msgs['procLog']: + for pl in self.msgs['procLog']: for x in pl.procLog.procs: if len(x.cmdline) > 0: n = list(x.cmdline)[0] plogs_by_proc[n].append(x) - print(plogs_by_proc.keys()) cpu_ok = True - dt = (self.service_msgs['procLog'][-1].logMonoTime - self.service_msgs['procLog'][0].logMonoTime) / 1e9 - for proc_name, expected_cpu in PROCS.items(): + dt = (self.msgs['procLog'][-1].logMonoTime - self.msgs['procLog'][0].logMonoTime) / 1e9 + header = ['process', 'usage', 'expected', 'max allowed', 'test result'] + rows = [] + for proc_name, expected in PROCS.items(): - err = "" - exp = "???" - cpu_usage = 0. + error = "" + usage = 0. x = plogs_by_proc[proc_name] if len(x) > 2: cpu_time = cputime_total(x[-1]) - cputime_total(x[0]) - cpu_usage = cpu_time / dt * 100. - - if isinstance(expected_cpu, tuple): - exp = str(expected_cpu) - minn, maxx = expected_cpu - else: - exp = f"{expected_cpu:5.2f}" - minn = min(expected_cpu * 0.65, max(expected_cpu - 1.0, 0.0)) - maxx = max(expected_cpu * 1.15, expected_cpu + 5.0) - - if cpu_usage > maxx: - err = "using more CPU than expected" - elif cpu_usage < minn: - err = "using less CPU than expected" - else: - err = "NO METRICS FOUND" + usage = cpu_time / dt * 100. + + max_allowed = max(expected * 1.8, expected + 5.0) + if usage > max_allowed: + error = "❌ USING MORE CPU THAN EXPECTED ❌" + cpu_ok = False - result += f"{proc_name.ljust(35)} {cpu_usage:5.2f}% ({exp}%) {err}\n" - if len(err) > 0: + else: + error = "❌ NO METRICS FOUND ❌" cpu_ok = False - result += "------------------------------------------------\n" + + rows.append([proc_name, usage, expected, max_allowed, error or "✅"]) + print(tabulate(rows, header, tablefmt="simple_grid", stralign="center", numalign="center", floatfmt=".2f")) # Ensure there's no missing procs - all_procs = {p.name for p in self.service_msgs['managerState'][0].managerState.processes if p.shouldBeRunning} + all_procs = {p.name for p in self.msgs['managerState'][0].managerState.processes if p.shouldBeRunning} for p in all_procs: with subtests.test(proc=p): assert any(p in pp for pp in PROCS.keys()), f"Expected CPU usage missing for {p}" @@ -299,16 +288,15 @@ class TestOnroad: procs_tot = sum([(max(x) if isinstance(x, tuple) else x) for x in PROCS.values()]) with subtests.test(name="total CPU"): assert procs_tot < MAX_TOTAL_CPU, "Total CPU budget exceeded" - result += "------------------------------------------------\n" - result += f"Total allocated CPU usage is {procs_tot}%, budget is {MAX_TOTAL_CPU}%, {MAX_TOTAL_CPU-procs_tot:.1f}% left\n" - result += "------------------------------------------------\n" - - print(result) + print("------------------------------------------------") + print(f"Total allocated CPU usage is {procs_tot}%, budget is {MAX_TOTAL_CPU}%, {MAX_TOTAL_CPU-procs_tot:.1f}% left") + print("------------------------------------------------") assert cpu_ok def test_memory_usage(self): - mems = [m.deviceState.memoryUsagePercent for m in self.service_msgs['deviceState']] + offset = int(SERVICE_LIST['deviceState'].frequency * LOG_OFFSET) + mems = [m.deviceState.memoryUsagePercent for m in self.msgs['deviceState'][offset:]] print("Memory usage: ", mems) # check for big leaks. note that memory usage is @@ -324,7 +312,9 @@ class TestOnroad: result += "-------------- ImgProc Timing ------------------\n" result += "------------------------------------------------\n" - ts = [getattr(m, m.which()).processingTime for m in self.lr if 'CameraState' in m.which()] + ts = [] + for s in ['roadCameraState', 'driverCameraState', 'wideCameraState']: + ts.extend(getattr(m, s).processingTime for m in self.msgs[s]) assert min(ts) < 0.025, f"high execution time: {min(ts)}" result += f"execution time: min {min(ts):.5f}s\n" result += f"execution time: max {max(ts):.5f}s\n" @@ -357,7 +347,7 @@ class TestOnroad: cfgs = [("longitudinalPlan", 0.05, 0.05),] for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).solverExecutionTime for m in self.service_msgs[s]] + ts = [getattr(m, s).solverExecutionTime for m in self.msgs[s]] assert max(ts) < instant_max, f"high '{s}' execution time: {max(ts)}" assert np.mean(ts) < avg_max, f"high avg '{s}' execution time: {np.mean(ts)}" result += f"'{s}' execution time: min {min(ts):.5f}s\n" @@ -377,7 +367,7 @@ class TestOnroad: ("driverStateV2", 0.050, 0.026), ] for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).modelExecutionTime for m in self.service_msgs[s]] + ts = [getattr(m, s).modelExecutionTime for m in self.msgs[s]] assert max(ts) < instant_max, f"high '{s}' execution time: {max(ts)}" assert np.mean(ts) < avg_max, f"high avg '{s}' execution time: {np.mean(ts)}" result += f"'{s}' execution time: min {min(ts):.5f}s\n" @@ -388,33 +378,32 @@ class TestOnroad: def test_timings(self): passed = True - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- Service Timings --------------\n" - result += "------------------------------------------------\n" + print("\n------------------------------------------------") + print("----------------- Service Timings --------------") + print("------------------------------------------------") + + header = ['service', 'max', 'min', 'mean', 'expected mean', 'rsd', 'max allowed rsd', 'test result'] + rows = [] for s, (maxmin, rsd) in TIMINGS.items(): - msgs = [m.logMonoTime for m in self.service_msgs[s]] + offset = int(SERVICE_LIST[s].frequency * LOG_OFFSET) + msgs = [m.logMonoTime for m in self.msgs[s][offset:]] if not len(msgs): raise Exception(f"missing {s}") ts = np.diff(msgs) / 1e9 dt = 1 / SERVICE_LIST[s].frequency - try: - np.testing.assert_allclose(np.mean(ts), dt, rtol=0.03, err_msg=f"{s} - failed mean timing check") - np.testing.assert_allclose([np.max(ts), np.min(ts)], dt, rtol=maxmin, err_msg=f"{s} - failed max/min timing check") - except Exception as e: - result += str(e) + "\n" - passed = False - - if np.std(ts) / dt > rsd: - result += f"{s} - failed RSD timing check\n" - passed = False - - result += f"{s.ljust(40)}: {np.array([np.mean(ts), np.max(ts), np.min(ts)])*1e3}\n" - result += f"{''.ljust(40)} {np.max(np.absolute([np.max(ts)/dt, np.min(ts)/dt]))} {np.std(ts)/dt}\n" - result += "="*67 - print(result) + errors = [] + if not np.allclose(np.mean(ts), dt, rtol=0.03, atol=0): + errors.append("❌ FAILED MEAN TIMING CHECK ❌") + if not np.allclose([np.max(ts), np.min(ts)], dt, rtol=maxmin, atol=0): + errors.append("❌ FAILED MAX/MIN TIMING CHECK ❌") + if (np.std(ts)/dt) > rsd: + errors.append("❌ FAILED RSD TIMING CHECK ❌") + passed = not errors + rows.append([s, *(np.array([np.max(ts), np.min(ts), np.mean(ts), dt])*1e3), np.std(ts)/dt, rsd, "\n".join(errors) or "✅"]) + + print(tabulate(rows, header, tablefmt="simple_grid", stralign="center", numalign="center", floatfmt=".2f")) assert passed @release_only @@ -430,11 +419,12 @@ class TestOnroad: def test_engagable(self): no_entries = Counter() - for m in self.service_msgs['onroadEvents']: + for m in self.msgs['onroadEvents']: for evt in m.onroadEvents: if evt.noEntry: no_entries[evt.name] += 1 - eng = [m.selfdriveState.engageable for m in self.service_msgs['selfdriveState']] + offset = int(SERVICE_LIST['selfdriveState'].frequency * LOG_OFFSET) + eng = [m.selfdriveState.engageable for m in self.msgs['selfdriveState'][offset:]] assert all(eng), \ f"Not engageable for whole segment:\n- selfdriveState.engageable: {Counter(eng)}\n- No entry events: {no_entries}" diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 19dcc625e2..81c18d03df 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -92,7 +92,7 @@ if GetOption('extras') and arch != "Darwin": ("openpilot", release), ("openpilot_test", f"{release}-staging"), ("openpilot_nightly", "nightly"), - ("openpilot_internal", "master"), + ("openpilot_internal", "nightly-dev"), ] cont = senv.Command(f"installer/continue_openpilot.o", f"installer/continue_openpilot.sh", @@ -110,3 +110,5 @@ if GetOption('extras') and arch != "Darwin": # build watch3 if arch in ['x86_64', 'aarch64', 'Darwin'] or GetOption('extras'): qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'msgq', 'visionipc']) + +SConscript(['raylib/SConscript']) diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc index c8245205ce..194b723fc9 100644 --- a/selfdrive/ui/qt/offroad/software_settings.cc +++ b/selfdrive/ui/qt/offroad/software_settings.cc @@ -54,7 +54,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { connect(targetBranchBtn, &ButtonControl::clicked, [=]() { auto current = params.get("GitBranch"); QStringList branches = QString::fromStdString(params.get("UpdaterAvailableBranches")).split(","); - for (QString b : {current.c_str(), "devel-staging", "devel", "nightly", "master-ci", "master"}) { + for (QString b : {current.c_str(), "devel-staging", "devel", "nightly", "nightly-dev", "master-ci", "master"}) { auto i = branches.indexOf(b); if (i >= 0) { branches.removeAt(i); diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index aff9b015b3..c716b6b4e9 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -408,7 +408,7 @@ Setup::Setup(QWidget *parent) : QStackedWidget(parent) { std::stringstream buffer; buffer << std::ifstream("/sys/class/hwmon/hwmon1/in1_input").rdbuf(); float voltage = (float)std::atoi(buffer.str().c_str()) / 1000.; - if (voltage < 7) { + if (voltage > 0 && voltage < 7) { addWidget(low_voltage()); } diff --git a/selfdrive/ui/raylib/.gitignore b/selfdrive/ui/raylib/.gitignore new file mode 100644 index 0000000000..c66ae096aa --- /dev/null +++ b/selfdrive/ui/raylib/.gitignore @@ -0,0 +1 @@ +_spinner diff --git a/selfdrive/ui/raylib/SConscript b/selfdrive/ui/raylib/SConscript new file mode 100644 index 0000000000..d603f263e1 --- /dev/null +++ b/selfdrive/ui/raylib/SConscript @@ -0,0 +1,17 @@ +Import('env', 'arch', 'common') + +raylib_env = env.Clone() +raylib_util_lib = env.Library("raylib_util_lib", ['util.cc'], LIBS='raylib') +linked_libs = ['raylib', raylib_util_lib, common] +raylib_env['LIBPATH'] += [f'#third_party/raylib/{arch}/'] + +mac_frameworks = [] +if arch == "Darwin": + mac_frameworks += ['OpenCL', 'CoreVideo', 'Cocoa', 'GLUT', 'CoreFoundation', 'OpenGL', 'IOKit'] +elif arch == 'larch64': + linked_libs += [] +else: + linked_libs += ['OpenCL', 'dl', 'pthread'] + +if arch != 'aarch64': + raylib_env.Program("_spinner", ["spinner.cc"], LIBS=linked_libs, FRAMEWORKS=mac_frameworks) diff --git a/selfdrive/ui/raylib/spinner.cc b/selfdrive/ui/raylib/spinner.cc new file mode 100644 index 0000000000..99aa5f3269 --- /dev/null +++ b/selfdrive/ui/raylib/spinner.cc @@ -0,0 +1,69 @@ +#include +#include +#include + +#include "selfdrive/ui/raylib/util.h" +#include "third_party/raylib/include/raylib.h" + +constexpr int kProgressBarWidth = 1000; +constexpr int kProgressBarHeight = 20; +constexpr float kRotationRate = 12.0f; +constexpr int kMargin = 200; +constexpr int kTextureSize = 360; +constexpr int kFontSize = 80; + +int main(int argc, char *argv[]) { + initApp("spinner", 30); + + // Turn off input buffering for std::cin + std::cin.sync_with_stdio(false); + std::cin.tie(nullptr); + + Texture2D commaTexture = LoadTextureResized("../../assets/img_spinner_comma.png", kTextureSize); + Texture2D spinnerTexture = LoadTextureResized("../../assets/img_spinner_track.png", kTextureSize); + + float rotation = 0.0f; + std::string userInput; + + while (!WindowShouldClose()) { + BeginDrawing(); + ClearBackground(BLACK); + + rotation = fmod(rotation + kRotationRate, 360.0f); + Vector2 center = {GetScreenWidth() / 2.0f, GetScreenHeight() / 2.0f}; + const Vector2 spinnerOrigin{kTextureSize / 2.0f, kTextureSize / 2.0f}; + const Vector2 commaPosition{center.x - kTextureSize / 2.0f, center.y - kTextureSize / 2.0f}; + + // Draw rotating spinner and static comma logo + DrawTexturePro(spinnerTexture, {0, 0, (float)kTextureSize, (float)kTextureSize}, + {center.x, center.y, (float)kTextureSize, (float)kTextureSize}, + spinnerOrigin, rotation, WHITE); + DrawTextureV(commaTexture, commaPosition, WHITE); + + // Check for user input + if (std::cin.rdbuf()->in_avail() > 0) { + std::getline(std::cin, userInput); + } + + // Display either a progress bar or user input text based on input + if (!userInput.empty()) { + float yPos = GetScreenHeight() - kMargin - kProgressBarHeight; + if (std::all_of(userInput.begin(), userInput.end(), ::isdigit)) { + Rectangle bar = {center.x - kProgressBarWidth / 2.0f, yPos, kProgressBarWidth, kProgressBarHeight}; + DrawRectangleRounded(bar, 0.5f, 10, GRAY); + + int progress = std::clamp(std::stoi(userInput), 0, 100); + bar.width *= progress / 100.0f; + DrawRectangleRounded(bar, 0.5f, 10, RAYWHITE); + } else { + Vector2 textSize = MeasureTextEx(getFont(), userInput.c_str(), kFontSize, 1.0); + DrawTextEx(getFont(), userInput.c_str(), {center.x - textSize.x / 2, yPos}, kFontSize, 1.0, WHITE); + } + } + + EndDrawing(); + } + + CloseWindow(); + return 0; +} diff --git a/selfdrive/ui/raylib/util.cc b/selfdrive/ui/raylib/util.cc new file mode 100644 index 0000000000..73c0e4e0b7 --- /dev/null +++ b/selfdrive/ui/raylib/util.cc @@ -0,0 +1,56 @@ +#include "selfdrive/ui/raylib/util.h" + +#include + +#undef GREEN +#undef RED +#undef YELLOW +#include "common/swaglog.h" +#include "system/hardware/hw.h" + +constexpr std::array(FontWeight::Count)> FONT_FILE_PATHS = { + "../../assets/fonts/Inter-Black.ttf", + "../../assets/fonts/Inter-Bold.ttf", + "../../assets/fonts/Inter-ExtraBold.ttf", + "../../assets/fonts/Inter-ExtraLight.ttf", + "../../assets/fonts/Inter-Medium.ttf", + "../../assets/fonts/Inter-Regular.ttf", + "../../assets/fonts/Inter-SemiBold.ttf", + "../../assets/fonts/Inter-Thin.ttf", +}; + +struct FontManager { + FontManager() { + for (int i = 0; i < fonts.size(); ++i) { + fonts[i] = LoadFontEx(FONT_FILE_PATHS[i], 120, nullptr, 250); + SetTextureFilter(fonts[i].texture, TEXTURE_FILTER_TRILINEAR); + } + } + + ~FontManager() { + for (auto &f : fonts) UnloadFont(f); + } + + std::array(FontWeight::Count)> fonts; +}; + +const Font& getFont(FontWeight weight) { + static FontManager font_manager; + return font_manager.fonts[(int)weight]; +} + +Texture2D LoadTextureResized(const char *fileName, int size) { + Image img = LoadImage(fileName); + ImageResize(&img, size, size); + Texture2D texture = LoadTextureFromImage(img); + SetTextureFilter(texture, TEXTURE_FILTER_TRILINEAR); + return texture; +} + +void initApp(const char *title, int fps) { + Hardware::set_display_power(true); + Hardware::set_brightness(65); + // SetTraceLogLevel(LOG_NONE); + InitWindow(0, 0, title); + SetTargetFPS(fps); +} diff --git a/selfdrive/ui/raylib/util.h b/selfdrive/ui/raylib/util.h new file mode 100644 index 0000000000..da2ec7118b --- /dev/null +++ b/selfdrive/ui/raylib/util.h @@ -0,0 +1,21 @@ +#pragma once + +#include + +#include "third_party/raylib/include/raylib.h" + +enum class FontWeight { + Normal, + Bold, + ExtraBold, + ExtraLight, + Medium, + Regular, + SemiBold, + Thin, + Count // To represent the total number of fonts +}; + +void initApp(const char *title, int fps); +const Font& getFont(FontWeight weight = FontWeight::Normal); +Texture2D LoadTextureResized(const char *fileName, int size); diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index 6a551b5afe..bca8cef363 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -117,11 +117,11 @@ DeveloperPanel Joystick Debug Mode - + وضع تصحيح أخطاء عصا التحكم Longitudinal Maneuver Mode - + وضع المناورة الطولية openpilot Longitudinal Control (Alpha) @@ -455,11 +455,11 @@ Waiting to start - + في انتظار البدء System Unresponsive - + النظام لا يستجيب @@ -651,7 +651,7 @@ This may take up to a minute. Developer - + المطور diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 56799790fa..c7107b3163 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -117,11 +117,11 @@ DeveloperPanel Joystick Debug Mode - + Modo de depuración de joystick Longitudinal Maneuver Mode - + Modo de maniobra longitudinal openpilot Longitudinal Control (Alpha) @@ -635,7 +635,7 @@ Esto puede tardar un minuto. Developer - + Desarrollador diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 92c94ab4bc..1ce2b0e16c 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -117,11 +117,11 @@ DeveloperPanel Joystick Debug Mode - + 조이스틱 디버그 모드 Longitudinal Maneuver Mode - + 롱컨 기동 모드 openpilot Longitudinal Control (Alpha) @@ -631,7 +631,7 @@ This may take up to a minute. Developer - + 개발자 diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 97df4ea75f..ff02fe4364 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -114,7 +114,7 @@ bool CameraBuf::acquire(int expo_time) { cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; } else { cur_yuv_buf = vipc_server->get_buffer(stream_type, cur_buf_idx); - cur_frame_data.processing_time = (double)(cur_frame_data.timestamp_end_of_isp - cur_frame_data.timestamp_eof)*1e-6; + cur_frame_data.processing_time = (double)(cur_frame_data.timestamp_end_of_isp - cur_frame_data.timestamp_eof)*1e-9; } VisionIpcBufExtra extra = { diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index fb325ac772..0c102051a5 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -55,7 +55,7 @@ public: float fl_pix = 0; - CameraState(SpectraMaster *master, const CameraConfig &config) : camera(master, config, true /*config.stream_type == VISION_STREAM_ROAD*/) {}; + CameraState(SpectraMaster *master, const CameraConfig &config) : camera(master, config, config.stream_type == VISION_STREAM_ROAD) {}; ~CameraState(); void init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc index e4ef3af404..5234ebd418 100644 --- a/system/camerad/sensors/ar0231.cc +++ b/system/camerad/sensors/ar0231.cc @@ -78,6 +78,7 @@ float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_r AR0231::AR0231() { image_sensor = cereal::FrameData::ImageSensor::AR0231; + bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR; pixel_size_mm = 0.003; data_word = true; frame_width = 1928; @@ -144,16 +145,19 @@ AR0231::AR0231() { 0x020007ff, 0x020007ff, 0x020007ff, 0x020007ff, 0x02000bff, 0x02000bff, 0x02000bff, 0x02000bff, 0x020017ff, 0x020017ff, 0x020017ff, 0x020017ff, - 0x020006ff, 0x020006ff, 0x020006ff, 0x020006ff, 0x02001bff, 0x02001bff, 0x02001bff, 0x02001bff, 0x020023ff, 0x020023ff, 0x020023ff, 0x020023ff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, }; for (int i = 0; i < 252; i++) { linearization_lut.push_back(0x0); } - linearization_pts = {0x07ff0bff, 0x17ff06ff, 0x1bff23ff, 0x3fff3fff}; + linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x23ff3fff, 0x3fff3fff}; + for (int i = 0; i < 884*2; i++) { + vignetting_lut.push_back(0xff); + } } void AR0231::processRegisters(uint8_t *cur_buf, cereal::FrameData::Builder &framed) const { diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc index 53ac37f08a..f6ba4504e1 100644 --- a/system/camerad/sensors/os04c10.cc +++ b/system/camerad/sensors/os04c10.cc @@ -22,6 +22,7 @@ const uint32_t os04c10_analog_gains_reg[] = { OS04C10::OS04C10() { image_sensor = cereal::FrameData::ImageSensor::OS04C10; + bayer_pattern = CAM_ISP_PATTERN_BAYER_BGBGBG; pixel_size_mm = 0.004; data_word = false; @@ -70,7 +71,7 @@ OS04C10::OS04C10() { }; for (int i = 0; i < 65; i++) { float fx = i / 64.0; - gamma_lut_rgb.push_back((uint32_t)(pow(fx, 0.7)*1023.0 + 0.5)); + gamma_lut_rgb.push_back((uint32_t)((10*fx)/(1+9*fx)*1023.0 + 0.5)); } prepare_gamma_lut(); linearization_lut = { @@ -78,16 +79,19 @@ OS04C10::OS04C10() { 0x020007ff, 0x020007ff, 0x020007ff, 0x020007ff, 0x02000bff, 0x02000bff, 0x02000bff, 0x02000bff, 0x020017ff, 0x020017ff, 0x020017ff, 0x020017ff, - 0x020006ff, 0x020006ff, 0x020006ff, 0x020006ff, 0x02001bff, 0x02001bff, 0x02001bff, 0x02001bff, 0x020023ff, 0x020023ff, 0x020023ff, 0x020023ff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, }; for (int i = 0; i < 252; i++) { linearization_lut.push_back(0x0); } - linearization_pts = {0x07ff0bff, 0x17ff06ff, 0x1bff23ff, 0x3fff3fff}; + linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x23ff3fff, 0x3fff3fff}; + for (int i = 0; i < 884*2; i++) { + vignetting_lut.push_back(0xff); + } } std::vector OS04C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { diff --git a/system/camerad/sensors/os04c10_cl.h b/system/camerad/sensors/os04c10_cl.h index 7cfc99655e..e285fb37e0 100644 --- a/system/camerad/sensors/os04c10_cl.h +++ b/system/camerad/sensors/os04c10_cl.h @@ -52,11 +52,7 @@ float3 color_correct(float3 rgb) { } float3 apply_gamma(float3 rgb, int expo_time) { - return powr(rgb, 0.7); -/*float s = log2((float)expo_time); - if (s < 6) {s = fmin(12.0 - s, 9.0);} - // log function adaptive to number of bits - return clamp(log(1 + rgb*(PV_MAX16 - BLACK_LVL)) * (0.48*s*s - 12.92*s + 115.0) - (1.08*s*s - 29.2*s + 260.0), 0.0, 255.0) / 255.0;*/ + return (10 * rgb) / (1 + 9 * rgb); } #endif diff --git a/system/camerad/sensors/ox03c10.cc b/system/camerad/sensors/ox03c10.cc index 19742661b1..d8cdc89648 100644 --- a/system/camerad/sensors/ox03c10.cc +++ b/system/camerad/sensors/ox03c10.cc @@ -25,6 +25,7 @@ const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 OX03C10::OX03C10() { image_sensor = cereal::FrameData::ImageSensor::OX03C10; + bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR; pixel_size_mm = 0.003; data_word = false; frame_width = 1928; @@ -80,9 +81,9 @@ OX03C10::OX03C10() { 0x00200000, 0x00200000, 0x00200000, 0x00200000, 0x00404080, 0x00404080, 0x00404080, 0x00404080, 0x00804100, 0x00804100, 0x00804100, 0x00804100, - 0x006b8402, 0x006b8402, 0x006b8402, 0x006b8402, - 0x00b8c070, 0x00b8c070, 0x00b8c070, 0x00b8c070, - 0x06044804, 0x06044804, 0x06044804, 0x06044804, + 0x02014402, 0x02014402, 0x02014402, 0x02014402, + 0x0402c804, 0x0402c804, 0x0402c804, 0x0402c804, + 0x0805d00a, 0x0805d00a, 0x0805d00a, 0x0805d00a, 0x100ba015, 0x100ba015, 0x100ba015, 0x100ba015, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, @@ -90,7 +91,7 @@ OX03C10::OX03C10() { for (int i = 0; i < 252; i++) { linearization_lut.push_back(0x0); } - linearization_pts = {0x07ff0bff, 0x17ff06ff, 0x1bff23ff, 0x27ff3fff}; + linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x1fff23ff, 0x27ff3fff}; for (int i = 0; i < 884*2; i++) { vignetting_lut.push_back(0xff); } diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index dc2aadfe13..1651fd8061 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -61,7 +61,7 @@ public: std::vector init_reg_array; uint32_t bits_per_pixel; - uint32_t bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR; + uint32_t bayer_pattern; uint32_t mipi_format; uint32_t mclk_frequency; uint32_t frame_data_type; diff --git a/system/camerad/test/test_camerad.py b/system/camerad/test/test_camerad.py index ada9594895..07a68e0020 100644 --- a/system/camerad/test/test_camerad.py +++ b/system/camerad/test/test_camerad.py @@ -9,7 +9,7 @@ from cereal import log from cereal.services import SERVICE_LIST from openpilot.system.manager.process_config import managed_processes -TEST_TIMESPAN = 30 +TEST_TIMESPAN = 10 LAG_FRAME_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 0.5, # ARs use synced pulses for frame starts log.FrameData.ImageSensor.ox03c10: 1.1} # OXs react to out-of-sync at next frame FRAME_DELTA_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 1.0, @@ -21,39 +21,40 @@ CAMERAS = ('roadCameraState', 'driverCameraState', 'wideRoadCameraState') @flaky(max_runs=3) @pytest.mark.tici class TestCamerad: - def setup_method(self): + @classmethod + def setup_class(cls): # run camerad and record logs managed_processes['camerad'].start() time.sleep(3) socks = {c: messaging.sub_sock(c, conflate=False, timeout=100) for c in CAMERAS} - self.logs = defaultdict(list) + cls.logs = defaultdict(list) start_time = time.monotonic() while time.monotonic()- start_time < TEST_TIMESPAN: for cam, s in socks.items(): - self.logs[cam] += messaging.drain_sock(s) + cls.logs[cam] += messaging.drain_sock(s) time.sleep(0.2) managed_processes['camerad'].stop() - self.log_by_frame_id = defaultdict(list) - self.sensor_type = None - for cam, msgs in self.logs.items(): - if self.sensor_type is None: - self.sensor_type = getattr(msgs[0], msgs[0].which()).sensor.raw + cls.log_by_frame_id = defaultdict(list) + cls.sensor_type = None + for cam, msgs in cls.logs.items(): + if cls.sensor_type is None: + cls.sensor_type = getattr(msgs[0], msgs[0].which()).sensor.raw expected_frames = SERVICE_LIST[cam].frequency * TEST_TIMESPAN assert expected_frames*0.95 < len(msgs) < expected_frames*1.05, f"unexpected frame count {cam}: {expected_frames=}, got {len(msgs)}" dts = np.abs(np.diff([getattr(m, m.which()).timestampSof/1e6 for m in msgs]) - 1000/SERVICE_LIST[cam].frequency) - assert (dts < FRAME_DELTA_TOLERANCE[self.sensor_type]).all(), f"{cam} dts(ms) out of spec: max diff {dts.max()}, 99 percentile {np.percentile(dts, 99)}" + assert (dts < FRAME_DELTA_TOLERANCE[cls.sensor_type]).all(), f"{cam} dts(ms) out of spec: max diff {dts.max()}, 99 percentile {np.percentile(dts, 99)}" for m in msgs: - self.log_by_frame_id[getattr(m, m.which()).frameId].append(m) + cls.log_by_frame_id[getattr(m, m.which()).frameId].append(m) # strip beginning and end for _ in range(3): - mn, mx = min(self.log_by_frame_id.keys()), max(self.log_by_frame_id.keys()) - del self.log_by_frame_id[mn] - del self.log_by_frame_id[mx] + mn, mx = min(cls.log_by_frame_id.keys()), max(cls.log_by_frame_id.keys()) + del cls.log_by_frame_id[mn] + del cls.log_by_frame_id[mx] def test_frame_skips(self): skips = {} diff --git a/system/hardware/hardwared.py b/system/hardware/hardwared.py index 9ebb9c9d54..da3172e8d1 100755 --- a/system/hardware/hardwared.py +++ b/system/hardware/hardwared.py @@ -148,8 +148,7 @@ def hw_state_thread(end_event, hw_queue): except queue.Full: pass - # TODO: remove this once the config is in AGNOS - if not modem_configured and len(HARDWARE.get_sim_info().get('sim_id', '')) > 0: + if not modem_configured and HARDWARE.get_modem_version() is not None: cloudlog.warning("configuring modem") HARDWARE.configure_modem() modem_configured = True @@ -316,7 +315,7 @@ def hardware_thread(end_event, hw_queue) -> None: set_offroad_alert_if_changed("Offroad_TemperatureTooHigh", show_alert, extra_text=extra_text) # TODO: this should move to TICI.initialize_hardware, but we currently can't import params there - if TICI: + if TICI and HARDWARE.get_device_type() == "tici": if not os.path.isfile("/persist/comma/living-in-the-moment"): if not Path("/data/media").is_mount(): set_offroad_alert_if_changed("Offroad_StorageMissing", True) diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 70049d1849..8110a0808e 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -467,8 +467,9 @@ class Tici(HardwareBase): cmds = [] if manufacturer == 'Cavli Inc.': cmds += [ - # use sim slot - 'AT^SIMSWAP=1', + 'AT^SIMSWAP=1', # use SIM slot, instead of internal eSIM + 'AT$QCSIMSLEEP=0', # disable SIM sleep + 'AT$QCSIMCFG=SimPowerSave,0', # more sleep disable # ethernet config 'AT$QCPCFG=usbNet,0', diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index 0ef34549b5..8598b2faa2 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -31,7 +31,7 @@ class Proc: PROCS = [ - Proc(['camerad'], 2.1, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), + Proc(['camerad'], 1.75, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), Proc(['dmonitoringmodeld'], 0.5, msgs=['driverStateV2']), Proc(['encoderd'], 0.23, msgs=[]), diff --git a/system/loggerd/tests/test_encoder.py b/system/loggerd/tests/test_encoder.py index 75862a9d45..cf38c8bc31 100644 --- a/system/loggerd/tests/test_encoder.py +++ b/system/loggerd/tests/test_encoder.py @@ -61,7 +61,7 @@ class TestEncoder: time.sleep(1.0) managed_processes['camerad'].start() - num_segments = int(os.getenv("SEGMENTS", random.randint(10, 15))) + num_segments = int(os.getenv("SEGMENTS", random.randint(2, 8))) # wait for loggerd to make the dir for first segment route_prefix_path = None diff --git a/system/loggerd/tests/test_uploader.py b/system/loggerd/tests/test_uploader.py index fa71600263..a05a28ee4e 100644 --- a/system/loggerd/tests/test_uploader.py +++ b/system/loggerd/tests/test_uploader.py @@ -73,7 +73,7 @@ class TestUploader(UploaderTestCase): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(2) self.join_thread() exp_order = self.gen_order([self.seg_num], []) @@ -91,7 +91,7 @@ class TestUploader(UploaderTestCase): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(2) self.join_thread() exp_order = self.gen_order([self.seg_num], []) @@ -110,7 +110,7 @@ class TestUploader(UploaderTestCase): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(2) self.join_thread() exp_order = self.gen_order([self.seg_num], []) @@ -137,7 +137,7 @@ class TestUploader(UploaderTestCase): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(2) self.join_thread() assert len(log_handler.upload_ignored) == 0, "Some files were ignored" @@ -155,7 +155,7 @@ class TestUploader(UploaderTestCase): f_paths = self.gen_files(lock=True, boot=False) # allow enough time that files should have been uploaded if they would be uploaded - time.sleep(5) + time.sleep(2) self.join_thread() for f_path in f_paths: @@ -168,7 +168,7 @@ class TestUploader(UploaderTestCase): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(2) self.join_thread() assert len(log_handler.upload_order) == 0, "File uploaded again" diff --git a/system/sentry.py b/system/sentry.py index 6b0332169b..63bf789b6f 100644 --- a/system/sentry.py +++ b/system/sentry.py @@ -63,8 +63,6 @@ def init(project: SentryProject) -> bool: max_value_length=8192, environment=env) - build_metadata = get_build_metadata() - sentry_sdk.set_user({"id": dongle_id}) sentry_sdk.set_tag("dirty", build_metadata.openpilot.is_dirty) sentry_sdk.set_tag("origin", build_metadata.openpilot.git_origin) diff --git a/system/tests/test_logmessaged.py b/system/tests/test_logmessaged.py index 3baf5300c0..03c13437bc 100644 --- a/system/tests/test_logmessaged.py +++ b/system/tests/test_logmessaged.py @@ -35,7 +35,7 @@ class TestLogmessaged: msgs = [f"abc {i}" for i in range(10)] for m in msgs: cloudlog.error(m) - time.sleep(3) + time.sleep(1) m = messaging.drain_sock(self.sock) assert len(m) == len(msgs) assert len(self._get_log_files()) >= 1 @@ -45,7 +45,7 @@ class TestLogmessaged: msg = "a"*3*1024*1024 for _ in range(n): cloudlog.info(msg) - time.sleep(3) + time.sleep(1) msgs = messaging.drain_sock(self.sock) assert len(msgs) == 0 diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index ee8f42ea72..189f8ac18f 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -51,7 +51,7 @@ MainWindow::MainWindow(AbstractStream *stream, const QString &dbc_file) : QMainW emit static_main_win->updateProgressBar(cur, total, success); }); qInstallMessageHandler([](QtMsgType type, const QMessageLogContext &context, const QString &msg) { - if (type == QtDebugMsg) std::cout << msg.toStdString() << std::endl; + if (type == QtDebugMsg) return; emit static_main_win->showMessage(msg, 2000); }); installMessageHandler([](ReplyMsgType type, const std::string msg) { qInfo() << msg.c_str(); }); diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 7f9e3d6960..3dddc0fb64 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -1,14 +1,12 @@ #include "tools/cabana/videowidget.h" #include -#include #include #include #include #include #include -#include #include #include #include @@ -27,9 +25,7 @@ static const QColor timeline_colors[] = { static Replay *getReplay() { auto stream = qobject_cast(can); - if (!stream) return nullptr; - - return stream->getReplay(); + return stream ? stream->getReplay() : nullptr; } VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) { @@ -144,13 +140,9 @@ QWidget *VideoWidget::createCameraWidget() { camera_tab->setAutoHide(true); camera_tab->setExpanding(false); - QStackedLayout *stacked = new QStackedLayout(); - stacked->setStackingMode(QStackedLayout::StackAll); - stacked->addWidget(cam_widget = new StreamCameraView("camerad", VISION_STREAM_ROAD)); + l->addWidget(cam_widget = new StreamCameraView("camerad", VISION_STREAM_ROAD)); cam_widget->setMinimumHeight(MIN_VIDEO_HEIGHT); cam_widget->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); - stacked->addWidget(alert_label = new InfoLabel(this)); - l->addLayout(stacked); l->addWidget(slider = new Slider(w)); slider->setSingleStep(0); @@ -165,16 +157,13 @@ QWidget *VideoWidget::createCameraWidget() { QObject::connect(camera_tab, &QTabBar::currentChanged, [this](int index) { if (index != -1) cam_widget->setStreamType((VisionStreamType)camera_tab->tabData(index).toInt()); }); - QObject::connect(static_cast(can), &ReplayStream::qLogLoaded, slider, &Slider::parseQLog, Qt::QueuedConnection); + QObject::connect(static_cast(can), &ReplayStream::qLogLoaded, cam_widget, &StreamCameraView::parseQLog, Qt::QueuedConnection); + slider->installEventFilter(cam_widget); return w; } void VideoWidget::vipcAvailableStreamsUpdated(std::set streams) { - static const QString stream_names[] = { - [VISION_STREAM_ROAD] = "Road camera", - [VISION_STREAM_WIDE_ROAD] = "Wide road camera", - [VISION_STREAM_DRIVER] = "Driver camera"}; - + static const QString stream_names[] = {"Road camera", "Driver camera", "Wide road camera"}; for (int i = 0; i < streams.size(); ++i) { if (camera_tab->count() <= i) { camera_tab->addTab(QString()); @@ -189,16 +178,9 @@ void VideoWidget::vipcAvailableStreamsUpdated(std::set streams } void VideoWidget::loopPlaybackClicked() { - auto replay = getReplay(); - if (!replay) return; - - if (replay->hasFlag(REPLAY_FLAG_NO_LOOP)) { - replay->removeFlag(REPLAY_FLAG_NO_LOOP); - loop_btn->setIcon("repeat"); - } else { - replay->addFlag(REPLAY_FLAG_NO_LOOP); - loop_btn->setIcon("repeat-1"); - } + bool is_looping = getReplay()->loop(); + getReplay()->setLoop(!is_looping); + loop_btn->setIcon(!is_looping ? "repeat" : "repeat-1"); } void VideoWidget::timeRangeChanged() { @@ -223,7 +205,9 @@ void VideoWidget::updateState() { if (!slider->isSliderDown()) { slider->setCurrentSecond(can->currentSec()); } - alert_label->showAlert(slider->alertInfo(can->currentSec())); + if (camera_tab->count() == 0) { // No streams available + cam_widget->update(); // Manually refresh to show alert events + } time_btn->setText(QString("%1 / %2").arg(formatTime(can->currentSec(), true), formatTime(slider->maximum() / slider->factor))); } else { @@ -239,41 +223,9 @@ void VideoWidget::updatePlayBtnState() { // Slider Slider::Slider(QWidget *parent) : QSlider(Qt::Horizontal, parent) { - thumbnail_label = new InfoLabel(parent); setMouseTracking(true); } -std::optional Slider::alertInfo(double seconds) { - return getReplay()->findAlertAtTime(seconds); -} - -QPixmap Slider::thumbnail(double seconds) { - auto it = thumbnails.lowerBound(can->toMonoTime(seconds)); - return it != thumbnails.end() ? it.value() : QPixmap(); -} - -void Slider::setTimeRange(double min, double max) { - assert(min < max); - setRange(min * factor, max * factor); -} - -void Slider::parseQLog(std::shared_ptr qlog) { - std::mutex mutex; - QtConcurrent::blockingMap(qlog->events.cbegin(), qlog->events.cend(), [&mutex, this](const Event &e) { - if (e.which == cereal::Event::Which::THUMBNAIL) { - capnp::FlatArrayMessageReader reader(e.data); - auto thumb = reader.getRoot().getThumbnail(); - auto data = thumb.getThumbnail(); - if (QPixmap pm; pm.loadFromData(data.begin(), data.size(), "jpeg")) { - QPixmap scaled = pm.scaledToHeight(MIN_VIDEO_HEIGHT - THUMBNAIL_MARGIN * 2, Qt::SmoothTransformation); - std::lock_guard lk(mutex); - thumbnails[thumb.getTimestampEof()] = scaled; - } - } - }); - update(); -} - void Slider::paintEvent(QPaintEvent *ev) { QPainter p(this); QRect r = rect().adjusted(0, 4, 0, -4); @@ -288,9 +240,8 @@ void Slider::paintEvent(QPaintEvent *ev) { p.fillRect(r, color); }; - auto replay = getReplay(); - if (replay) { - for (const auto &entry: *replay->getTimeline()) { + if (auto replay = getReplay()) { + for (const auto &entry : *replay->getTimeline()) { fillRange(entry.start_time, entry.end_time, timeline_colors[(int)entry.type]); } @@ -319,84 +270,7 @@ void Slider::mousePressEvent(QMouseEvent *e) { } } -void Slider::mouseMoveEvent(QMouseEvent *e) { - int pos = std::clamp(e->pos().x(), 0, width()); - double seconds = (minimum() + pos * ((maximum() - minimum()) / (double)width())) / factor; - QPixmap thumb = thumbnail(seconds); - if (!thumb.isNull()) { - int x = std::clamp(pos - thumb.width() / 2, THUMBNAIL_MARGIN, width() - thumb.width() - THUMBNAIL_MARGIN + 1); - int y = -thumb.height() - THUMBNAIL_MARGIN; - thumbnail_label->showPixmap(mapToParent(QPoint(x, y)), utils::formatSeconds(seconds), thumb, alertInfo(seconds)); - } else { - thumbnail_label->hide(); - } - QSlider::mouseMoveEvent(e); -} - -bool Slider::event(QEvent *event) { - switch (event->type()) { - case QEvent::WindowActivate: - case QEvent::WindowDeactivate: - case QEvent::FocusIn: - case QEvent::FocusOut: - case QEvent::Leave: - thumbnail_label->hide(); - break; - default: - break; - } - return QSlider::event(event); -} - -// InfoLabel - -InfoLabel::InfoLabel(QWidget *parent) : QWidget(parent, Qt::WindowStaysOnTopHint) { - setAttribute(Qt::WA_ShowWithoutActivating); - setAttribute(Qt::WA_TransparentForMouseEvents); - setVisible(false); -} - -void InfoLabel::showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm, const std::optional &alert) { - second = sec; - pixmap = pm; - alert_info = alert; - setGeometry(QRect(pt, pm.size())); - setVisible(true); - update(); -} - -void InfoLabel::showAlert(const std::optional &alert) { - alert_info = alert; - pixmap = {}; - setVisible(alert_info.has_value()); - update(); -} - -void InfoLabel::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setPen(QPen(palette().color(QPalette::BrightText), 2)); - if (!pixmap.isNull()) { - p.drawPixmap(0, 0, pixmap); - p.drawRect(rect()); - p.drawText(rect().adjusted(0, 0, 0, -THUMBNAIL_MARGIN), second, Qt::AlignHCenter | Qt::AlignBottom); - } - if (alert_info) { - QColor color = timeline_colors[int(alert_info->type)]; - color.setAlphaF(0.5); - QString text = QString::fromStdString(alert_info->text1); - if (!alert_info->text2.empty()) text += "\n" + QString::fromStdString(alert_info->text2); - - if (!pixmap.isNull()) { - QFont font; - font.setPixelSize(11); - p.setFont(font); - } - QRect text_rect = rect().adjusted(1, 1, -1, -1); - QRect r = p.fontMetrics().boundingRect(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); - p.fillRect(text_rect.left(), r.top(), text_rect.width(), r.height(), color); - p.drawText(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); - } -} +// StreamCameraView StreamCameraView::StreamCameraView(std::string stream_name, VisionStreamType stream_type, QWidget *parent) : CameraWidget(stream_name, stream_type, parent) { @@ -404,15 +278,93 @@ StreamCameraView::StreamCameraView(std::string stream_name, VisionStreamType str fade_animation->setDuration(500); fade_animation->setStartValue(0.2f); fade_animation->setEndValue(0.7f); + fade_animation->setEasingCurve(QEasingCurve::InOutQuad); + connect(fade_animation, &QPropertyAnimation::valueChanged, this, QOverload<>::of(&StreamCameraView::update)); +} + +void StreamCameraView::parseQLog(std::shared_ptr qlog) { + std::mutex mutex; + QtConcurrent::blockingMap(qlog->events.cbegin(), qlog->events.cend(), [this, &mutex](const Event &e) { + if (e.which == cereal::Event::Which::THUMBNAIL) { + capnp::FlatArrayMessageReader reader(e.data); + auto thumb_data = reader.getRoot().getThumbnail(); + auto image_data = thumb_data.getThumbnail(); + if (QPixmap thumb; thumb.loadFromData(image_data.begin(), image_data.size(), "jpeg")) { + QPixmap generated_thumb = generateThumbnail(thumb, can->toSeconds(thumb_data.getTimestampEof())); + std::lock_guard lock(mutex); + thumbnails[thumb_data.getTimestampEof()] = generated_thumb; + } + } + }); + update(); } void StreamCameraView::paintGL() { CameraWidget::paintGL(); + QPainter p(this); + if (auto alert = getReplay()->findAlertAtTime(can->currentSec())) { + drawAlert(p, rect(), *alert); + } + if (thumbnail_pt_) { + drawThumbnail(p); + } if (can->isPaused()) { - QPainter p(this); - p.setPen(QColor(200, 200, 200, static_cast(255 * overlay_opacity))); + p.setPen(QColor(200, 200, 200, static_cast(255 * fade_animation->currentValue().toFloat()))); p.setFont(QFont(font().family(), 16, QFont::Bold)); p.drawText(rect(), Qt::AlignCenter, tr("PAUSED")); } } + +QPixmap StreamCameraView::generateThumbnail(QPixmap thumb, double seconds) { + QPixmap scaled = thumb.scaledToHeight(MIN_VIDEO_HEIGHT - THUMBNAIL_MARGIN * 2, Qt::SmoothTransformation); + QPainter p(&scaled); + p.setPen(QPen(palette().color(QPalette::BrightText), 2)); + p.drawRect(scaled.rect()); + if (auto alert = getReplay()->findAlertAtTime(seconds)) { + p.setFont(QFont(font().family(), 10)); + drawAlert(p, scaled.rect(), *alert); + } + return scaled; +} + +void StreamCameraView::drawThumbnail(QPainter &p) { + int pos = std::clamp(thumbnail_pt_->x(), 0, width()); + auto [min_sec, max_sec] = can->timeRange().value_or(std::make_pair(can->minSeconds(), can->maxSeconds())); + double seconds = min_sec + pos * (max_sec - min_sec) / width(); + + auto it = thumbnails.lowerBound(can->toMonoTime(seconds)); + if (it != thumbnails.end()) { + const QPixmap &thumb = it.value(); + int x = std::clamp(pos - thumb.width() / 2, THUMBNAIL_MARGIN, width() - thumb.width() - THUMBNAIL_MARGIN + 1); + int y = height() - thumb.height() - THUMBNAIL_MARGIN; + + p.drawPixmap(x, y, thumb); + p.setPen(QPen(palette().color(QPalette::BrightText), 2)); + p.drawText(x, y, thumb.width(), thumb.height() - THUMBNAIL_MARGIN, Qt::AlignHCenter | Qt::AlignBottom, QString::number(seconds)); + } +} + +void StreamCameraView::drawAlert(QPainter &p, const QRect &rect, const Timeline::Entry &alert) { + p.setPen(QPen(palette().color(QPalette::BrightText), 2)); + QColor color = timeline_colors[int(alert.type)]; + color.setAlphaF(0.5); + QString text = QString::fromStdString(alert.text1); + if (!alert.text2.empty()) text += "\n" + QString::fromStdString(alert.text2); + + QRect text_rect = rect.adjusted(1, 1, -1, -1); + QRect r = p.fontMetrics().boundingRect(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); + p.fillRect(text_rect.left(), r.top(), text_rect.width(), r.height(), color); + p.drawText(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); +} + +bool StreamCameraView::eventFilter(QObject *, QEvent *event) { + if (event->type() == QEvent::MouseMove) { + thumbnail_pt_ = static_cast(event)->pos(); + update(); + } else if (event->type() == QEvent::Leave) { + thumbnail_pt_ = std::nullopt; + update(); + } + return false; +} diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index d3342c34d7..78503365e5 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -1,6 +1,5 @@ #pragma once -#include #include #include #include @@ -18,17 +17,6 @@ #include "tools/replay/logreader.h" #include "tools/cabana/streams/replaystream.h" -class InfoLabel : public QWidget { -public: - InfoLabel(QWidget *parent); - void showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm, const std::optional &alert); - void showAlert(const std::optional &alert); - void paintEvent(QPaintEvent *event) override; - QPixmap pixmap; - QString second; - std::optional alert_info; -}; - class Slider : public QSlider { Q_OBJECT @@ -36,40 +24,30 @@ public: Slider(QWidget *parent); double currentSecond() const { return value() / factor; } void setCurrentSecond(double sec) { setValue(sec * factor); } - void setTimeRange(double min, double max); - std::optional alertInfo(double sec); - QPixmap thumbnail(double sec); - void parseQLog(std::shared_ptr qlog); - - const double factor = 1000.0; - -private: + void setTimeRange(double min, double max) { setRange(min * factor, max * factor); } void mousePressEvent(QMouseEvent *e) override; - void mouseMoveEvent(QMouseEvent *e) override; - bool event(QEvent *event) override; void paintEvent(QPaintEvent *ev) override; - - QMap thumbnails; - InfoLabel *thumbnail_label; + const double factor = 1000.0; }; class StreamCameraView : public CameraWidget { Q_OBJECT - Q_PROPERTY(float overlayOpacity READ overlayOpacity WRITE setOverlayOpacity) public: StreamCameraView(std::string stream_name, VisionStreamType stream_type, QWidget *parent = nullptr); void paintGL() override; void showPausedOverlay() { fade_animation->start(); } - float overlayOpacity() const { return overlay_opacity; } - void setOverlayOpacity(float opacity) { - overlay_opacity = opacity; - update(); - } + void parseQLog(std::shared_ptr qlog); private: - float overlay_opacity; + QPixmap generateThumbnail(QPixmap thumbnail, double seconds); + void drawAlert(QPainter &p, const QRect &rect, const Timeline::Entry &alert); + void drawThumbnail(QPainter &p); + bool eventFilter(QObject *obj, QEvent *event) override; + QPropertyAnimation *fade_animation; + QMap thumbnails; + std::optional thumbnail_pt_; }; class VideoWidget : public QFrame { @@ -96,7 +74,6 @@ protected: ToolButton *loop_btn = nullptr; QToolButton *speed_btn = nullptr; ToolButton *skip_to_end_btn = nullptr; - InfoLabel *alert_label = nullptr; Slider *slider = nullptr; QTabBar *camera_tab = nullptr; }; diff --git a/tools/car_porting/test_car_model.py b/tools/car_porting/test_car_model.py index 6f274aaf69..dd248f562e 100755 --- a/tools/car_porting/test_car_model.py +++ b/tools/car_porting/test_car_model.py @@ -5,14 +5,14 @@ import unittest # noqa: TID251 from opendbc.car.tests.routes import CarTestRoute from openpilot.selfdrive.car.tests.test_models import TestCarModel -from openpilot.tools.lib.route import SegmentName +from openpilot.tools.lib.route import SegmentRange -def create_test_models_suite(routes: list[CarTestRoute], ci=False) -> unittest.TestSuite: +def create_test_models_suite(routes: list[CarTestRoute]) -> unittest.TestSuite: test_suite = unittest.TestSuite() for test_route in routes: # create new test case and discover tests - test_case_args = {"platform": test_route.car_model, "test_route": test_route, "test_route_on_bucket": ci} + test_case_args = {"platform": test_route.car_model, "test_route": test_route} CarModelTestCase = type("CarModelTestCase", (TestCarModel,), test_case_args) test_suite.addTest(unittest.TestLoader().loadTestsFromTestCase(CarModelTestCase)) return test_suite @@ -23,16 +23,14 @@ if __name__ == "__main__": "Uses selfdrive/car/tests/test_models.py") parser.add_argument("route_or_segment_name", help="Specify route to run tests on") parser.add_argument("--car", help="Specify car model for test route") - parser.add_argument("--ci", action="store_true", help="Attempt to get logs using openpilotci, need to specify car") args = parser.parse_args() if len(sys.argv) == 1: parser.print_help() sys.exit() - route_or_segment_name = SegmentName(args.route_or_segment_name.strip(), allow_route_name=True) - segment_num = route_or_segment_name.segment_num if route_or_segment_name.segment_num != -1 else None + sr = SegmentRange(args.route_or_segment_name) - test_route = CarTestRoute(route_or_segment_name.route_name.canonical_name, args.car, segment=segment_num) - test_suite = create_test_models_suite([test_route], ci=args.ci) + test_routes = [CarTestRoute(sr.route_name, args.car, segment=seg_idx) for seg_idx in sr.seg_idxs] + test_suite = create_test_models_suite(test_routes) unittest.TextTestRunner().run(test_suite) diff --git a/tools/install_python_dependencies.sh b/tools/install_python_dependencies.sh index 7657457744..267577d712 100755 --- a/tools/install_python_dependencies.sh +++ b/tools/install_python_dependencies.sh @@ -24,9 +24,8 @@ function update_uv() { if ! command -v "uv" > /dev/null 2>&1; then echo "installing uv..." curl -LsSf https://astral.sh/uv/install.sh | sh - UV_BIN="$HOME/.cargo/env" - ADD_PATH_CMD=". \"$UV_BIN\"" - eval "$ADD_PATH_CMD" + UV_BIN="$HOME/.local/bin" + PATH="$UV_BIN:$PATH" fi echo "updating uv..." diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index f8c000c259..3e3aed34a9 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -31,6 +31,8 @@ def joystickd_thread(): CC.enabled = sm['selfdriveState'].enabled CC.latActive = sm['selfdriveState'].active and not sm['carState'].steerFaultTemporary and not sm['carState'].steerFaultPermanent CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in sm['onroadEvents']) and CP.openpilotLongitudinalControl + CC.cruiseControl.cancel = sm['carState'].cruiseState.enabled and (not CC.enabled or not CP.pcmCruise) + CC.hudControl.leadDistanceBars = 2 actuators = CC.actuators diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index 963d7a8cdb..8206ad2228 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -12,6 +12,7 @@ def internal_source_available(url=DATA_ENDPOINT): hostname = urlparse(url).hostname port = urlparse(url).port or 80 with socket.socket(socket.AF_INET,socket.SOCK_STREAM) as s: + s.settimeout(0.5) s.connect((hostname, port)) return True except (socket.gaierror, ConnectionRefusedError): diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index f038469e94..aed972f606 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -121,6 +121,7 @@ def report(platform, route, _description, CP, ID, maneuvers): buffer = io.BytesIO() fig.savefig(buffer, format='webp') + plt.close(fig) buffer.seek(0) builder.append(f"\n") builder.append("\n") diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index b10ffa1ac0..6c6e252a57 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import numpy as np from dataclasses import dataclass from cereal import messaging, car @@ -10,8 +11,11 @@ from openpilot.common.swaglog import cloudlog @dataclass class Action: - accel: float # m/s^2 - duration: float # seconds + accel_bp: list[float] # m/s^2 + time_bp: list[float] # seconds + + def __post_init__(self): + assert len(self.accel_bp) == len(self.time_bp) @dataclass @@ -41,11 +45,12 @@ class Maneuver: return min(max(self.initial_speed - v_ego, -2.), 2.) action = self.actions[self._action_index] + action_accel = np.interp(self._action_frames * DT_MDL, action.time_bp, action.accel_bp) self._action_frames += 1 # reached duration of action - if self._action_frames > (action.duration / DT_MDL): + if self._action_frames > (action.time_bp[-1] / DT_MDL): # next action if self._action_index < len(self.actions) - 1: self._action_index += 1 @@ -60,7 +65,7 @@ class Maneuver: else: self._finished = True - return action.accel + return float(action_accel) @property def finished(self): @@ -74,47 +79,47 @@ class Maneuver: MANEUVERS = [ Maneuver( "come to stop", - [Action(-0.5, 12)], + [Action([-0.5], [12])], repeat=2, initial_speed=5., ), Maneuver( - "start from stop", - [Action(1.5, 5)], - repeat=2, - initial_speed=0., + "start from stop", + [Action([1.5], [6])], + repeat=2, + initial_speed=0., ), Maneuver( - "creep: alternate between +1m/s^2 and -1m/s^2", - [ - Action(1, 3), Action(-1, 3), - Action(1, 3), Action(-1, 3), - Action(1, 3), Action(-1, 3), - ], - repeat=2, - initial_speed=0., + "creep: alternate between +1m/s^2 and -1m/s^2", + [ + Action([1], [3]), Action([-1], [3]), + Action([1], [3]), Action([-1], [3]), + Action([1], [3]), Action([-1], [3]), + ], + repeat=2, + initial_speed=0., ), Maneuver( "brake step response: -1m/s^2 from 20mph", - [Action(-1, 3)], + [Action([-1], [3])], repeat=2, initial_speed=20. * CV.MPH_TO_MS, ), Maneuver( "brake step response: -4m/s^2 from 20mph", - [Action(-4, 3)], + [Action([-4], [3])], repeat=2, initial_speed=20. * CV.MPH_TO_MS, ), Maneuver( "gas step response: +1m/s^2 from 20mph", - [Action(1, 3)], + [Action([1], [3])], repeat=2, initial_speed=20. * CV.MPH_TO_MS, ), Maneuver( "gas step response: +4m/s^2 from 20mph", - [Action(4, 3)], + [Action([4], [3])], repeat=2, initial_speed=20. * CV.MPH_TO_MS, ), diff --git a/tools/replay/replay.h b/tools/replay/replay.h index d3f5425308..0b4906532e 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -60,8 +60,8 @@ public: inline int segmentCacheLimit() const { return segment_cache_limit; } inline void setSegmentCacheLimit(int n) { segment_cache_limit = std::max(MIN_SEGMENTS_CACHE, n); } inline bool hasFlag(REPLAY_FLAGS flag) const { return flags_ & flag; } - inline void addFlag(REPLAY_FLAGS flag) { flags_ |= flag; } - inline void removeFlag(REPLAY_FLAGS flag) { flags_ &= ~flag; } + void setLoop(bool loop) { loop ? flags_ &= ~REPLAY_FLAG_NO_LOOP : flags_ |= REPLAY_FLAG_NO_LOOP; } + bool loop() const { return !(flags_ & REPLAY_FLAG_NO_LOOP); } inline const Route* route() const { return route_.get(); } inline double currentSeconds() const { return double(cur_mono_time_ - route_start_ts_) / 1e9; } inline std::time_t routeDateTime() const { return route_date_time_; } diff --git a/tools/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc index d350df570a..e4d8c3e5f0 100644 --- a/tools/replay/tests/test_replay.cc +++ b/tools/replay/tests/test_replay.cc @@ -136,7 +136,7 @@ std::string download_demo_route() { } -TEST_CASE("Local route") { +TEST_CASE("Getting route") { std::string data_dir = download_demo_route(); auto flags = GENERATE(0, REPLAY_FLAG_QCAMERA); @@ -148,16 +148,6 @@ TEST_CASE("Local route") { } } -TEST_CASE("Remote route") { - auto flags = GENERATE(0, REPLAY_FLAG_QCAMERA); - Route route(DEMO_ROUTE); - REQUIRE(route.load()); - REQUIRE(route.segments().size() == 13); - for (int i = 0; i < TEST_REPLAY_SEGMENTS; ++i) { - read_segment(i, route.at(i), flags); - } -} - TEST_CASE("seek_to") { QEventLoop loop; int seek_to = util::random_int(0, 2 * 59); diff --git a/tools/replay/timeline.cc b/tools/replay/timeline.cc index 5a4f58a46f..8c33e95f11 100644 --- a/tools/replay/timeline.cc +++ b/tools/replay/timeline.cc @@ -70,11 +70,11 @@ void Timeline::buildTimeline(const Route &route, uint64_t route_start_ts, bool l } } - callback(log); // Notify the callback once the log is processed - // Sort and finalize the timeline entries std::sort(staging_entries_.begin(), staging_entries_.end(), [](auto &a, auto &b) { return a.start_time < b.start_time; }); timeline_entries_ = std::make_shared>(staging_entries_); + + callback(log); // Notify the callback once the log is processed } } diff --git a/uv.lock b/uv.lock index 54b488a9f0..358423275d 100644 --- a/uv.lock +++ b/uv.lock @@ -145,16 +145,16 @@ wheels = [ [[package]] name = "azure-core" -version = "1.31.0" +version = "1.32.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "requests" }, { name = "six" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/03/7a/f79ad135a276a37e61168495697c14ba1721a52c3eab4dae2941929c79f8/azure_core-1.31.0.tar.gz", hash = "sha256:656a0dd61e1869b1506b7c6a3b31d62f15984b1a573d6326f6aa2f3e4123284b", size = 277147 } +sdist = { url = "https://files.pythonhosted.org/packages/cc/ee/668328306a9e963a5ad9f152cd98c7adad86c822729fd1d2a01613ad1e67/azure_core-1.32.0.tar.gz", hash = "sha256:22b3c35d6b2dae14990f6c1be2912bf23ffe50b220e708a28ab1bb92b1c730e5", size = 279128 } wheels = [ - { url = "https://files.pythonhosted.org/packages/01/8e/fcb6a77d3029d2a7356f38dbc77cf7daa113b81ddab76b5593d23321e44c/azure_core-1.31.0-py3-none-any.whl", hash = "sha256:22954de3777e0250029360ef31d80448ef1be13b80a459bff80ba7073379e2cd", size = 197399 }, + { url = "https://files.pythonhosted.org/packages/39/83/325bf5e02504dbd8b4faa98197a44cdf8a325ef259b48326a2b6f17f8383/azure_core-1.32.0-py3-none-any.whl", hash = "sha256:eac191a0efb23bfa83fddf321b27b122b4ec847befa3091fa736a5c32c50d7b4", size = 198855 }, ] [[package]] @@ -1243,7 +1243,7 @@ wheels = [ [[package]] name = "onnxruntime" -version = "1.19.2" +version = "1.20.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "coloredlogs" }, @@ -1254,15 +1254,15 @@ dependencies = [ { name = "sympy" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/f3/78/e29f5fb76e0f6524f3520e8e5b9d53282784b45d14068c5112db9f712b0a/onnxruntime-1.19.2-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c1dfe4f660a71b31caa81fc298a25f9612815215a47b286236e61d540350d7b6", size = 11496005 }, - { url = "https://files.pythonhosted.org/packages/60/ce/be4152da5c1030ab5a159a4a792ed9abad6ba498d79ef0aeba593ff7b5bf/onnxruntime-1.19.2-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a36511dc07c5c964b916697e42e366fa43c48cdb3d3503578d78cef30417cb84", size = 13167809 }, - { url = "https://files.pythonhosted.org/packages/47/64/da42254ec14452cad2cdd4cf407094841c0a378c0d08944e9a36172197e9/onnxruntime-1.19.2-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d2d366fbcc205ce68a8a3bde2185fd15c604d9645888703785b61ef174265168", size = 11486028 }, - { url = "https://files.pythonhosted.org/packages/b2/92/3574f6836f33b1b25f272293e72538c38451b12c2d9aa08630bb6bc0f057/onnxruntime-1.19.2-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:477b93df4db467e9cbf34051662a4b27c18e131fa1836e05974eae0d6e4cf29b", size = 13175054 }, + { url = "https://files.pythonhosted.org/packages/ef/db/f9f3a2cac589f557c1227d27e288eeb248830613dd1a5b5c17f26894e802/onnxruntime-1.20.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:8a831b720d0a7be8241a230cb06f592e8bb66652d7cea54ce02d83769651fdee", size = 11946136 }, + { url = "https://files.pythonhosted.org/packages/53/d8/93706484c8e0db2dfde8559e74b5a9ab74d203a0471671121188c212f7cb/onnxruntime-1.20.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:041fefe60af844ebd90f344c84f908201490555cd0a6d78dd0a7acdc27b59972", size = 13318583 }, + { url = "https://files.pythonhosted.org/packages/8d/bd/4b15cfc8242577376ed8eb8f10239422945cfa7e52b89db487ceea912c3b/onnxruntime-1.20.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:51e7b34e398089c4ed8d0f50722d7a64a4d5f11b38c4a42576458a03c6dbc72e", size = 11942243 }, + { url = "https://files.pythonhosted.org/packages/ba/db/7e65fcf45f5485193158999c194470f40be4bb6c82ec7e70401f78220dec/onnxruntime-1.20.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0e259378ff2843321e0bf4552adcbee48822c91d77d42dde78b87dcdf10ad01f", size = 13313619 }, ] [[package]] name = "onnxruntime-gpu" -version = "1.19.2" +version = "1.20.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "coloredlogs" }, @@ -1273,8 +1273,8 @@ dependencies = [ { name = "sympy" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/85/33/06e856502a1d482532cfa7d4c7ca775dfddcd851c7bd1833f5177e567055/onnxruntime_gpu-1.19.2-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:562fc7c755393eaad9751e56149339dd201ffbfdb3ef5f43ff21d0619ba9045f", size = 226175096 }, - { url = "https://files.pythonhosted.org/packages/68/55/49e5b4b4d6e9a8841dcdec2f102069716b626bf6ce9640b832a9497504eb/onnxruntime_gpu-1.19.2-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:554a02a3fac0119707eb87327908afd21c4e6f0fa5bf9a034398f098adc316c5", size = 226163139 }, + { url = "https://files.pythonhosted.org/packages/60/d0/9baa124f0276a186175c4e819d62ed75416096b0f7ff058296989d4712ff/onnxruntime_gpu-1.20.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6338fdfc955489b1d4329498f7f07640c000f92eae8933de293adc5f5ed480f5", size = 291504604 }, + { url = "https://files.pythonhosted.org/packages/ed/cd/98ea1ef90c5e51de69239881522a4c115a009dba99d83fd8e2606b33358d/onnxruntime_gpu-1.20.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:06398420c363b7e400de98deb8bc238fcff98adafe8eeda6ff96a94e20713ac0", size = 291507294 }, ] [[package]] @@ -1459,11 +1459,11 @@ requires-dist = [ [[package]] name = "packaging" -version = "24.1" +version = "24.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/51/65/50db4dda066951078f0a96cf12f4b9ada6e4b811516bf0262c0f4f7064d4/packaging-24.1.tar.gz", hash = "sha256:026ed72c8ed3fcce5bf8950572258698927fd1dbda10a5e981cdf0ac37f4f002", size = 148788 } +sdist = { url = "https://files.pythonhosted.org/packages/d0/63/68dbb6eb2de9cb10ee4c9c14a0148804425e13c4fb20d61cce69f53106da/packaging-24.2.tar.gz", hash = "sha256:c228a6dc5e932d346bc5739379109d49e8853dd8223571c7c5b55260edc0b97f", size = 163950 } wheels = [ - { url = "https://files.pythonhosted.org/packages/08/aa/cc0199a5f0ad350994d660967a8efb233fe0416e4639146c089643407ce6/packaging-24.1-py3-none-any.whl", hash = "sha256:5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124", size = 53985 }, + { url = "https://files.pythonhosted.org/packages/88/ef/eb23f262cca3c0c4eb7ab1933c3b1f03d021f2c48f54763065b6f0e321be/packaging-24.2-py3-none-any.whl", hash = "sha256:09abb1bccd265c01f4a3aa3f7a7db064b36514d2cba19a2f694fe6150451a759", size = 65451 }, ] [[package]] @@ -4454,15 +4454,15 @@ wheels = [ [[package]] name = "pytest-cov" -version = "5.0.0" +version = "6.0.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "coverage", extra = ["toml"] }, { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/74/67/00efc8d11b630c56f15f4ad9c7f9223f1e5ec275aaae3fa9118c6a223ad2/pytest-cov-5.0.0.tar.gz", hash = "sha256:5837b58e9f6ebd335b0f8060eecce69b662415b16dc503883a02f45dfeb14857", size = 63042 } +sdist = { url = "https://files.pythonhosted.org/packages/be/45/9b538de8cef30e17c7b45ef42f538a94889ed6a16f2387a6c89e73220651/pytest-cov-6.0.0.tar.gz", hash = "sha256:fde0b595ca248bb8e2d76f020b465f3b107c9632e6a1d1705f17834c89dcadc0", size = 66945 } wheels = [ - { url = "https://files.pythonhosted.org/packages/78/3a/af5b4fa5961d9a1e6237b530eb87dd04aea6eb83da09d2a4073d81b54ccf/pytest_cov-5.0.0-py3-none-any.whl", hash = "sha256:4f0764a1219df53214206bf1feea4633c3b558a2925c8b59f144f682861ce652", size = 21990 }, + { url = "https://files.pythonhosted.org/packages/36/3b/48e79f2cd6a61dbbd4807b4ed46cb564b4fd50a76166b1c4ea5c1d9e2371/pytest_cov-6.0.0-py3-none-any.whl", hash = "sha256:eee6f1b9e61008bd34975a4d5bab25801eb31898b032dd55addc93e96fcaaa35", size = 22949 }, ] [[package]] @@ -4736,7 +4736,7 @@ wheels = [ [[package]] name = "rerun-sdk" -version = "0.19.0" +version = "0.19.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "attrs" }, @@ -4746,11 +4746,11 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/c4/59/cfea9527a2f56652c9f2e54151c8a0d2b572b7f1255ca9bc6ea8ad2fd7ce/rerun_sdk-0.19.0-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:49a48d6d5d7de662ef3e83dc262e65705fa719726f6bc6deefad27c4b6d34e98", size = 37415314 }, - { url = "https://files.pythonhosted.org/packages/d9/16/0d7099d537bf2f73988ac93f5075d4fd717e96c25697b3ea16af8bcc2cda/rerun_sdk-0.19.0-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:c8012b4e517a911a782472dc97ebbdc6ed4261b44bfdd0e0a0c64496f17ddc91", size = 35743438 }, - { url = "https://files.pythonhosted.org/packages/cf/35/eaabd19deaa2bbb121df3a6949206f02ad6cff122d8ad6ba0fcdeeb972c6/rerun_sdk-0.19.0-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:65bb8ddf9611827c31d5502f9d1ee997c1facbbdf5dce9a268f0aa6bcaea5439", size = 39794278 }, - { url = "https://files.pythonhosted.org/packages/8b/2c/1e06376a531431855c4ea12865aba0d83a1a1d0537a544191d09d3b44eea/rerun_sdk-0.19.0-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:6a49fde1c9d0691166402707ec3b317bf0d82fb1b4412b98e02ccbf499d9b92d", size = 41301646 }, - { url = "https://files.pythonhosted.org/packages/b2/57/948b518f3db30b8dd27d1dc0280acc6510289a79675dcb523ccfcced39d6/rerun_sdk-0.19.0-cp38-abi3-win_amd64.whl", hash = "sha256:da304927485cb4e6afe25ea8ed84c0cb7e63f3ba8ce2c72a1034ae1ffc69a6c0", size = 33573220 }, + { url = "https://files.pythonhosted.org/packages/48/b0/2f91b886fd701e3ded8e3013852e833519f2e640b857e1b0c0883c7a7d37/rerun_sdk-0.19.1-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:a61be3afea5ac856809bdff7234a21de308f149f92d5f4d4c532dcd5698de1c4", size = 37403183 }, + { url = "https://files.pythonhosted.org/packages/4e/96/6e75b675d20ee584f3f3664aead70bc1736b958091c14b2a5a06f4f31881/rerun_sdk-0.19.1-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:56bb01adf13308725b1534b93be21ad6234ecfa98db13227dc281a3cb8b41922", size = 35748606 }, + { url = "https://files.pythonhosted.org/packages/ed/e6/086f38552edeaebd227a47711f67be2cee9f07483694278daab0f87321f1/rerun_sdk-0.19.1-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:caa7bef1e63bb1c95d0cf52812cf16855b80c7b1d0137b6c2ba9e5031c35c095", size = 39801474 }, + { url = "https://files.pythonhosted.org/packages/e4/91/631883fdacd12630b0a37d42a6e8c87785b9c8cfba68aed21aa6e7c73723/rerun_sdk-0.19.1-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:7a638d2009c5248ce61feadf283d1b10e98241e04a5834c8d27169a4401ed5b1", size = 41311782 }, + { url = "https://files.pythonhosted.org/packages/c7/46/5f0ab6fd81e4e109915a886f572648e47b1d159c4c5369c81c4b57089c55/rerun_sdk-0.19.1-cp38-abi3-win_amd64.whl", hash = "sha256:5d7950ed35cfa0ecaad302dbc2413354654dd0d5cd44e73cb55d05fa1ed0004d", size = 33581988 }, ] [[package]] @@ -4800,27 +4800,27 @@ wheels = [ [[package]] name = "ruff" -version = "0.7.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a6/21/5c6e05e0fd3fbb41be4fb92edbc9a04de70baf60adb61435ce0c6b8c3d55/ruff-0.7.1.tar.gz", hash = "sha256:9d8a41d4aa2dad1575adb98a82870cf5db5f76b2938cf2206c22c940034a36f4", size = 3181670 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/65/45/8a20a9920175c9c4892b2420f80ff3cf14949cf3067118e212f9acd9c908/ruff-0.7.1-py3-none-linux_armv6l.whl", hash = "sha256:cb1bc5ed9403daa7da05475d615739cc0212e861b7306f314379d958592aaa89", size = 10389268 }, - { url = "https://files.pythonhosted.org/packages/1b/d3/2f8382db2cf4f9488e938602e33e36287f9d26cb283aa31f11c31297ce79/ruff-0.7.1-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:27c1c52a8d199a257ff1e5582d078eab7145129aa02721815ca8fa4f9612dc35", size = 10188348 }, - { url = "https://files.pythonhosted.org/packages/a2/31/7d14e2a88da351200f844b7be889a0845d9e797162cf76b136d21b832a23/ruff-0.7.1-py3-none-macosx_11_0_arm64.whl", hash = "sha256:588a34e1ef2ea55b4ddfec26bbe76bc866e92523d8c6cdec5e8aceefeff02d99", size = 9841448 }, - { url = "https://files.pythonhosted.org/packages/db/99/738cafdc768eceeca0bd26c6f03e213aa91203d2278e1d95b1c31c4ece41/ruff-0.7.1-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:94fc32f9cdf72dc75c451e5f072758b118ab8100727168a3df58502b43a599ca", size = 10674864 }, - { url = "https://files.pythonhosted.org/packages/fe/12/bcf2836b50eab53c65008383e7d55201e490d75167c474f14a16e1af47d2/ruff-0.7.1-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:985818742b833bffa543a84d1cc11b5e6871de1b4e0ac3060a59a2bae3969250", size = 10192105 }, - { url = "https://files.pythonhosted.org/packages/2b/71/261d5d668bf98b6c44e89bfb5dfa4cb8cb6c8b490a201a3d8030e136ea4f/ruff-0.7.1-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:32f1e8a192e261366c702c5fb2ece9f68d26625f198a25c408861c16dc2dea9c", size = 11194144 }, - { url = "https://files.pythonhosted.org/packages/90/1f/0926d18a3b566fa6e7b3b36093088e4ffef6b6ba4ea85a462d9a93f7e35c/ruff-0.7.1-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:699085bf05819588551b11751eff33e9ca58b1b86a6843e1b082a7de40da1565", size = 11917066 }, - { url = "https://files.pythonhosted.org/packages/cd/a8/9fac41f128b6a44ab4409c1493430b4ee4b11521e8aeeca19bfe1ce851f9/ruff-0.7.1-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:344cc2b0814047dc8c3a8ff2cd1f3d808bb23c6658db830d25147339d9bf9ea7", size = 11458821 }, - { url = "https://files.pythonhosted.org/packages/25/cd/59644168f086ab13fe4e02943b9489a0aa710171f66b178e179df5383554/ruff-0.7.1-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4316bbf69d5a859cc937890c7ac7a6551252b6a01b1d2c97e8fc96e45a7c8b4a", size = 12700379 }, - { url = "https://files.pythonhosted.org/packages/fb/30/3bac63619eb97174661829c07fc46b2055a053dee72da29d7c304c1cd2c0/ruff-0.7.1-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:79d3af9dca4c56043e738a4d6dd1e9444b6d6c10598ac52d146e331eb155a8ad", size = 11019813 }, - { url = "https://files.pythonhosted.org/packages/4b/af/f567b885b5cb3bcdbcca3458ebf210cc8c9c7a9f61c332d3c2a050c3b21e/ruff-0.7.1-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:c5c121b46abde94a505175524e51891f829414e093cd8326d6e741ecfc0a9112", size = 10662146 }, - { url = "https://files.pythonhosted.org/packages/bc/ad/eb930d3ad117a9f2f7261969c21559ebd82bb13b6e8001c7caed0d44be5f/ruff-0.7.1-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:8422104078324ea250886954e48f1373a8fe7de59283d747c3a7eca050b4e378", size = 10256911 }, - { url = "https://files.pythonhosted.org/packages/20/d5/af292ce70a016fcec792105ca67f768b403dd480a11888bc1f418fed0dd5/ruff-0.7.1-py3-none-musllinux_1_2_i686.whl", hash = "sha256:56aad830af8a9db644e80098fe4984a948e2b6fc2e73891538f43bbe478461b8", size = 10767488 }, - { url = "https://files.pythonhosted.org/packages/24/85/cc04a3bd027f433bebd2a097e63b3167653c079f7f13d8f9a1178e693412/ruff-0.7.1-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:658304f02f68d3a83c998ad8bf91f9b4f53e93e5412b8f2388359d55869727fd", size = 11093368 }, - { url = "https://files.pythonhosted.org/packages/0b/fb/c39cbf32d1f3e318674b8622f989417231794926b573f76dd4d0ca49f0f1/ruff-0.7.1-py3-none-win32.whl", hash = "sha256:b517a2011333eb7ce2d402652ecaa0ac1a30c114fbbd55c6b8ee466a7f600ee9", size = 8594180 }, - { url = "https://files.pythonhosted.org/packages/5a/71/ec8cdea34ecb90c830ca60d54ac7b509a7b5eab50fae27e001d4470fe813/ruff-0.7.1-py3-none-win_amd64.whl", hash = "sha256:f38c41fcde1728736b4eb2b18850f6d1e3eedd9678c914dede554a70d5241307", size = 9419751 }, - { url = "https://files.pythonhosted.org/packages/79/7b/884553415e9f0a9bf358ed52fb68b934e67ef6c5a62397ace924a1afdf9a/ruff-0.7.1-py3-none-win_arm64.whl", hash = "sha256:19aa200ec824c0f36d0c9114c8ec0087082021732979a359d6f3c390a6ff2a37", size = 8717402 }, +version = "0.7.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/4b/06/09d1276df977eece383d0ed66052fc24ec4550a61f8fbc0a11200e690496/ruff-0.7.3.tar.gz", hash = "sha256:e1d1ba2e40b6e71a61b063354d04be669ab0d39c352461f3d789cac68b54a313", size = 3243664 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c0/56/933d433c2489e4642487b835f53dd9ff015fb3d8fa459b09bb2ce42d7c4b/ruff-0.7.3-py3-none-linux_armv6l.whl", hash = "sha256:34f2339dc22687ec7e7002792d1f50712bf84a13d5152e75712ac08be565d344", size = 10372090 }, + { url = "https://files.pythonhosted.org/packages/20/ea/1f0a22a6bcdd3fc26c73f63a025d05bd565901b729d56bcb093c722a6c4c/ruff-0.7.3-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:fb397332a1879b9764a3455a0bb1087bda876c2db8aca3a3cbb67b3dbce8cda0", size = 10190037 }, + { url = "https://files.pythonhosted.org/packages/16/74/aca75666e0d481fe394e76a8647c44ea919087748024924baa1a17371e3e/ruff-0.7.3-py3-none-macosx_11_0_arm64.whl", hash = "sha256:37d0b619546103274e7f62643d14e1adcbccb242efda4e4bdb9544d7764782e9", size = 9811998 }, + { url = "https://files.pythonhosted.org/packages/20/a1/cf446a0d7f78ea1f0bd2b9171c11dfe746585c0c4a734b25966121eb4f5d/ruff-0.7.3-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d59f0c3ee4d1a6787614e7135b72e21024875266101142a09a61439cb6e38a5", size = 10620626 }, + { url = "https://files.pythonhosted.org/packages/cd/c1/82b27d09286ae855f5d03b1ad37cf243f21eb0081732d4d7b0d658d439cb/ruff-0.7.3-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:44eb93c2499a169d49fafd07bc62ac89b1bc800b197e50ff4633aed212569299", size = 10177598 }, + { url = "https://files.pythonhosted.org/packages/b9/42/c0acac22753bf74013d035a5ef6c5c4c40ad4d6686bfb3fda7c6f37d9b37/ruff-0.7.3-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6d0242ce53f3a576c35ee32d907475a8d569944c0407f91d207c8af5be5dae4e", size = 11171963 }, + { url = "https://files.pythonhosted.org/packages/43/18/bb0befb7fb9121dd9009e6a72eb98e24f1bacb07c6f3ecb55f032ba98aed/ruff-0.7.3-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:6b6224af8b5e09772c2ecb8dc9f3f344c1aa48201c7f07e7315367f6dd90ac29", size = 11856157 }, + { url = "https://files.pythonhosted.org/packages/5e/91/04e98d7d6e32eca9d1372be595f9abc7b7f048795e32eb2edbd8794d50bd/ruff-0.7.3-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c50f95a82b94421c964fae4c27c0242890a20fe67d203d127e84fbb8013855f5", size = 11440331 }, + { url = "https://files.pythonhosted.org/packages/f5/dc/3fe99f2ce10b76d389041a1b9f99e7066332e479435d4bebcceea16caff5/ruff-0.7.3-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7f3eff9961b5d2644bcf1616c606e93baa2d6b349e8aa8b035f654df252c8c67", size = 12725354 }, + { url = "https://files.pythonhosted.org/packages/43/7b/1daa712de1c5bc6cbbf9fa60e9c41cc48cda962dc6d2c4f2a224d2c3007e/ruff-0.7.3-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b8963cab06d130c4df2fd52c84e9f10d297826d2e8169ae0c798b6221be1d1d2", size = 11010091 }, + { url = "https://files.pythonhosted.org/packages/b6/db/1227a903587432eb569e57a95b15a4f191a71fe315cde4c0312df7bc85da/ruff-0.7.3-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:61b46049d6edc0e4317fb14b33bd693245281a3007288b68a3f5b74a22a0746d", size = 10610687 }, + { url = "https://files.pythonhosted.org/packages/db/e2/dc41ee90c3085aadad4da614d310d834f641aaafddf3dfbba08210c616ce/ruff-0.7.3-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:10ebce7696afe4644e8c1a23b3cf8c0f2193a310c18387c06e583ae9ef284de2", size = 10254843 }, + { url = "https://files.pythonhosted.org/packages/6f/09/5f6cac1c91542bc5bd33d40b4c13b637bf64d7bb29e091dadb01b62527fe/ruff-0.7.3-py3-none-musllinux_1_2_i686.whl", hash = "sha256:3f36d56326b3aef8eeee150b700e519880d1aab92f471eefdef656fd57492aa2", size = 10730962 }, + { url = "https://files.pythonhosted.org/packages/d3/42/89a4b9a24ef7d00269e24086c417a006f9a3ffeac2c80f2629eb5ce140ee/ruff-0.7.3-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:5d024301109a0007b78d57ab0ba190087b43dce852e552734ebf0b0b85e4fb16", size = 11101907 }, + { url = "https://files.pythonhosted.org/packages/b0/5c/efdb4777686683a8edce94ffd812783bddcd3d2454d38c5ac193fef7c500/ruff-0.7.3-py3-none-win32.whl", hash = "sha256:4ba81a5f0c5478aa61674c5a2194de8b02652f17addf8dfc40c8937e6e7d79fc", size = 8611095 }, + { url = "https://files.pythonhosted.org/packages/bb/b8/28fbc6a4efa50178f973972d1c84b2d0a33cdc731588522ab751ac3da2f5/ruff-0.7.3-py3-none-win_amd64.whl", hash = "sha256:588a9ff2fecf01025ed065fe28809cd5a53b43505f48b69a1ac7707b1b7e4088", size = 9418283 }, + { url = "https://files.pythonhosted.org/packages/3f/77/b587cba6febd5e2003374f37eb89633f79f161e71084f94057c8653b7fb3/ruff-0.7.3-py3-none-win_arm64.whl", hash = "sha256:1713e2c5545863cdbfe2cbce21f69ffaf37b813bfd1fb3b90dc9a6f1963f5a8c", size = 8725228 }, ] [[package]] @@ -4834,15 +4834,15 @@ wheels = [ [[package]] name = "sentry-sdk" -version = "2.17.0" +version = "2.18.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b1/83/7d0956a71ac894717099be3669ca7b8f164bccbcfb570b2f02817d0a0068/sentry_sdk-2.17.0.tar.gz", hash = "sha256:dd0a05352b78ffeacced73a94e86f38b32e2eae15fff5f30ca5abb568a72eacf", size = 290959 } +sdist = { url = "https://files.pythonhosted.org/packages/24/cc/0d87cc8246f52d92228aa6718a24e1988a2893f4abe2f64ec5a8bcba4185/sentry_sdk-2.18.0.tar.gz", hash = "sha256:0dc21febd1ab35c648391c664df96f5f79fb0d92d7d4225cd9832e53a617cafd", size = 293615 } wheels = [ - { url = "https://files.pythonhosted.org/packages/10/63/8e80fff3aa15488bc332ede44165a397a29bb13ec4a4b2236299e3b66067/sentry_sdk-2.17.0-py2.py3-none-any.whl", hash = "sha256:625955884b862cc58748920f9e21efdfb8e0d4f98cca4ab0d3918576d5b606ad", size = 314520 }, + { url = "https://files.pythonhosted.org/packages/76/9b/2d512efdb0de203d1f0312fae53433c3009ba70b0078421d25baaedc960a/sentry_sdk-2.18.0-py2.py3-none-any.whl", hash = "sha256:ee70e27d1bbe4cd52a38e1bd28a5fadb9b17bc29d91b5f2b97ae29c0a7610442", size = 317514 }, ] [[package]] @@ -4879,11 +4879,11 @@ wheels = [ [[package]] name = "setuptools" -version = "75.2.0" +version = "75.3.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/07/37/b31be7e4b9f13b59cde9dcaeff112d401d49e0dc5b37ed4a9fc8fb12f409/setuptools-75.2.0.tar.gz", hash = "sha256:753bb6ebf1f465a1912e19ed1d41f403a79173a9acf66a42e7e6aec45c3c16ec", size = 1350308 } +sdist = { url = "https://files.pythonhosted.org/packages/ed/22/a438e0caa4576f8c383fa4d35f1cc01655a46c75be358960d815bfbb12bd/setuptools-75.3.0.tar.gz", hash = "sha256:fba5dd4d766e97be1b1681d98712680ae8f2f26d7881245f2ce9e40714f1a686", size = 1351577 } wheels = [ - { url = "https://files.pythonhosted.org/packages/31/2d/90165d51ecd38f9a02c6832198c13a4e48652485e2ccf863ebb942c531b6/setuptools-75.2.0-py3-none-any.whl", hash = "sha256:a7fcb66f68b4d9e8e66b42f9876150a3371558f98fa32222ffaa5bced76406f8", size = 1249825 }, + { url = "https://files.pythonhosted.org/packages/90/12/282ee9bce8b58130cb762fbc9beabd531549952cac11fc56add11dcb7ea0/setuptools-75.3.0-py3-none-any.whl", hash = "sha256:f2504966861356aa38616760c0f66568e535562374995367b4e69c7143cf6bcd", size = 1251070 }, ] [[package]] @@ -5009,14 +5009,14 @@ wheels = [ [[package]] name = "tqdm" -version = "4.66.6" +version = "4.67.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "colorama", marker = "platform_system == 'Windows'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e9/34/bef135b27fe1864993a5284ad001157ee9b5538e859ac90f5b0e8cc8c9ec/tqdm-4.66.6.tar.gz", hash = "sha256:4bdd694238bef1485ce839d67967ab50af8f9272aab687c0d7702a01da0be090", size = 169533 } +sdist = { url = "https://files.pythonhosted.org/packages/e8/4f/0153c21dc5779a49a0598c445b1978126b1344bab9ee71e53e44877e14e0/tqdm-4.67.0.tar.gz", hash = "sha256:fe5a6f95e6fe0b9755e9469b77b9c3cf850048224ecaa8293d7d2d31f97d869a", size = 169739 } wheels = [ - { url = "https://files.pythonhosted.org/packages/41/73/02342de9c2d20922115f787e101527b831c0cffd2105c946c4a4826bcfd4/tqdm-4.66.6-py3-none-any.whl", hash = "sha256:223e8b5359c2efc4b30555531f09e9f2f3589bcd7fdd389271191031b49b7a63", size = 78326 }, + { url = "https://files.pythonhosted.org/packages/2b/78/57043611a16c655c8350b4c01b8d6abfb38cc2acb475238b62c2146186d7/tqdm-4.67.0-py3-none-any.whl", hash = "sha256:0cd8af9d56911acab92182e88d763100d4788bdf421d251616040cc4d44863be", size = 78590 }, ] [[package]] @@ -5060,26 +5060,26 @@ wheels = [ [[package]] name = "watchdog" -version = "5.0.3" +version = "6.0.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a2/48/a86139aaeab2db0a2482676f64798d8ac4d2dbb457523f50ab37bf02ce2c/watchdog-5.0.3.tar.gz", hash = "sha256:108f42a7f0345042a854d4d0ad0834b741d421330d5f575b81cb27b883500176", size = 129556 } +sdist = { url = "https://files.pythonhosted.org/packages/db/7d/7f3d619e951c88ed75c6037b246ddcf2d322812ee8ea189be89511721d54/watchdog-6.0.0.tar.gz", hash = "sha256:9ddf7c82fda3ae8e24decda1338ede66e1c99883db93711d8fb941eaa2d8c282", size = 131220 } wheels = [ - { url = "https://files.pythonhosted.org/packages/70/34/946f08602f8b8e6af45bc725e4a8013975a34883ab5570bd0d827a4c9829/watchdog-5.0.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f01f4a3565a387080dc49bdd1fefe4ecc77f894991b88ef927edbfa45eb10818", size = 96650 }, - { url = "https://files.pythonhosted.org/packages/96/2b/b84e35d49e8b0bad77e5d086fc1e2c6c833bbfe74d53144cfe8b26117eff/watchdog-5.0.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:91b522adc25614cdeaf91f7897800b82c13b4b8ac68a42ca959f992f6990c490", size = 88653 }, - { url = "https://files.pythonhosted.org/packages/d5/3f/41b5d77c10f450b79921c17b7d0b416616048867bfe63acaa072a619a0cb/watchdog-5.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d52db5beb5e476e6853da2e2d24dbbbed6797b449c8bf7ea118a4ee0d2c9040e", size = 89286 }, - { url = "https://files.pythonhosted.org/packages/1c/9b/8b206a928c188fdeb7b12e1c795199534cd44bdef223b8470129016009dd/watchdog-5.0.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:94d11b07c64f63f49876e0ab8042ae034674c8653bfcdaa8c4b32e71cfff87e8", size = 96739 }, - { url = "https://files.pythonhosted.org/packages/e1/26/129ca9cd0f8016672f37000010c2fedc0b86816e894ebdc0af9bb04a6439/watchdog-5.0.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:349c9488e1d85d0a58e8cb14222d2c51cbc801ce11ac3936ab4c3af986536926", size = 88708 }, - { url = "https://files.pythonhosted.org/packages/8f/b3/5e10ec32f0c429cdb55b1369066d6e83faf9985b3a53a4e37bb5c5e29aa0/watchdog-5.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:53a3f10b62c2d569e260f96e8d966463dec1a50fa4f1b22aec69e3f91025060e", size = 89309 }, - { url = "https://files.pythonhosted.org/packages/60/33/7cb71c9df9a77b6927ee5f48d25e1de5562ce0fa7e0c56dcf2b0472e64a2/watchdog-5.0.3-py3-none-manylinux2014_aarch64.whl", hash = "sha256:dd021efa85970bd4824acacbb922066159d0f9e546389a4743d56919b6758b91", size = 79335 }, - { url = "https://files.pythonhosted.org/packages/f6/91/320bc1496cf951a3cf93a7ffd18a581f0792c304be963d943e0e608c2919/watchdog-5.0.3-py3-none-manylinux2014_armv7l.whl", hash = "sha256:78864cc8f23dbee55be34cc1494632a7ba30263951b5b2e8fc8286b95845f82c", size = 79334 }, - { url = "https://files.pythonhosted.org/packages/8b/2c/567c5e042ed667d3544c43d48a65cf853450a2d2a9089d9523a65f195e94/watchdog-5.0.3-py3-none-manylinux2014_i686.whl", hash = "sha256:1e9679245e3ea6498494b3028b90c7b25dbb2abe65c7d07423ecfc2d6218ff7c", size = 79333 }, - { url = "https://files.pythonhosted.org/packages/c3/f0/64059fe162ef3274662e67bbdea6c45b3cd53e846d5bd1365fcdc3dc1d15/watchdog-5.0.3-py3-none-manylinux2014_ppc64.whl", hash = "sha256:9413384f26b5d050b6978e6fcd0c1e7f0539be7a4f1a885061473c5deaa57221", size = 79334 }, - { url = "https://files.pythonhosted.org/packages/f6/d9/19b7d02965be2801e2d0f6f4bde23e4ae172620071b65430fa0c2f8441ac/watchdog-5.0.3-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:294b7a598974b8e2c6123d19ef15de9abcd282b0fbbdbc4d23dfa812959a9e05", size = 79333 }, - { url = "https://files.pythonhosted.org/packages/cb/a1/5393ac6d0b095d3a44946b09258e9b5f22cb2fb67bcfa419dd868478826c/watchdog-5.0.3-py3-none-manylinux2014_s390x.whl", hash = "sha256:26dd201857d702bdf9d78c273cafcab5871dd29343748524695cecffa44a8d97", size = 79332 }, - { url = "https://files.pythonhosted.org/packages/a0/58/edec25190b6403caf4426dd418234f2358a106634b7d6aa4aec6939b104f/watchdog-5.0.3-py3-none-manylinux2014_x86_64.whl", hash = "sha256:0f9332243355643d567697c3e3fa07330a1d1abf981611654a1f2bf2175612b7", size = 79334 }, - { url = "https://files.pythonhosted.org/packages/97/69/cfb2d17ba8aabc73be2e2d03c8c319b1f32053a02c4b571852983aa24ff2/watchdog-5.0.3-py3-none-win32.whl", hash = "sha256:c66f80ee5b602a9c7ab66e3c9f36026590a0902db3aea414d59a2f55188c1f49", size = 79320 }, - { url = "https://files.pythonhosted.org/packages/91/b4/2b5b59358dadfa2c8676322f955b6c22cde4937602f40490e2f7403e548e/watchdog-5.0.3-py3-none-win_amd64.whl", hash = "sha256:f00b4cf737f568be9665563347a910f8bdc76f88c2970121c86243c8cfdf90e9", size = 79325 }, - { url = "https://files.pythonhosted.org/packages/38/b8/0aa69337651b3005f161f7f494e59188a1d8d94171666900d26d29d10f69/watchdog-5.0.3-py3-none-win_ia64.whl", hash = "sha256:49f4d36cb315c25ea0d946e018c01bb028048023b9e103d3d3943f58e109dd45", size = 79324 }, + { url = "https://files.pythonhosted.org/packages/e0/24/d9be5cd6642a6aa68352ded4b4b10fb0d7889cb7f45814fb92cecd35f101/watchdog-6.0.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6eb11feb5a0d452ee41f824e271ca311a09e250441c262ca2fd7ebcf2461a06c", size = 96393 }, + { url = "https://files.pythonhosted.org/packages/63/7a/6013b0d8dbc56adca7fdd4f0beed381c59f6752341b12fa0886fa7afc78b/watchdog-6.0.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ef810fbf7b781a5a593894e4f439773830bdecb885e6880d957d5b9382a960d2", size = 88392 }, + { url = "https://files.pythonhosted.org/packages/d1/40/b75381494851556de56281e053700e46bff5b37bf4c7267e858640af5a7f/watchdog-6.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:afd0fe1b2270917c5e23c2a65ce50c2a4abb63daafb0d419fde368e272a76b7c", size = 89019 }, + { url = "https://files.pythonhosted.org/packages/39/ea/3930d07dafc9e286ed356a679aa02d777c06e9bfd1164fa7c19c288a5483/watchdog-6.0.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:bdd4e6f14b8b18c334febb9c4425a878a2ac20efd1e0b231978e7b150f92a948", size = 96471 }, + { url = "https://files.pythonhosted.org/packages/12/87/48361531f70b1f87928b045df868a9fd4e253d9ae087fa4cf3f7113be363/watchdog-6.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:c7c15dda13c4eb00d6fb6fc508b3c0ed88b9d5d374056b239c4ad1611125c860", size = 88449 }, + { url = "https://files.pythonhosted.org/packages/5b/7e/8f322f5e600812e6f9a31b75d242631068ca8f4ef0582dd3ae6e72daecc8/watchdog-6.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6f10cb2d5902447c7d0da897e2c6768bca89174d0c6e1e30abec5421af97a5b0", size = 89054 }, + { url = "https://files.pythonhosted.org/packages/a9/c7/ca4bf3e518cb57a686b2feb4f55a1892fd9a3dd13f470fca14e00f80ea36/watchdog-6.0.0-py3-none-manylinux2014_aarch64.whl", hash = "sha256:7607498efa04a3542ae3e05e64da8202e58159aa1fa4acddf7678d34a35d4f13", size = 79079 }, + { url = "https://files.pythonhosted.org/packages/5c/51/d46dc9332f9a647593c947b4b88e2381c8dfc0942d15b8edc0310fa4abb1/watchdog-6.0.0-py3-none-manylinux2014_armv7l.whl", hash = "sha256:9041567ee8953024c83343288ccc458fd0a2d811d6a0fd68c4c22609e3490379", size = 79078 }, + { url = "https://files.pythonhosted.org/packages/d4/57/04edbf5e169cd318d5f07b4766fee38e825d64b6913ca157ca32d1a42267/watchdog-6.0.0-py3-none-manylinux2014_i686.whl", hash = "sha256:82dc3e3143c7e38ec49d61af98d6558288c415eac98486a5c581726e0737c00e", size = 79076 }, + { url = "https://files.pythonhosted.org/packages/ab/cc/da8422b300e13cb187d2203f20b9253e91058aaf7db65b74142013478e66/watchdog-6.0.0-py3-none-manylinux2014_ppc64.whl", hash = "sha256:212ac9b8bf1161dc91bd09c048048a95ca3a4c4f5e5d4a7d1b1a7d5752a7f96f", size = 79077 }, + { url = "https://files.pythonhosted.org/packages/2c/3b/b8964e04ae1a025c44ba8e4291f86e97fac443bca31de8bd98d3263d2fcf/watchdog-6.0.0-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:e3df4cbb9a450c6d49318f6d14f4bbc80d763fa587ba46ec86f99f9e6876bb26", size = 79078 }, + { url = "https://files.pythonhosted.org/packages/62/ae/a696eb424bedff7407801c257d4b1afda455fe40821a2be430e173660e81/watchdog-6.0.0-py3-none-manylinux2014_s390x.whl", hash = "sha256:2cce7cfc2008eb51feb6aab51251fd79b85d9894e98ba847408f662b3395ca3c", size = 79077 }, + { url = "https://files.pythonhosted.org/packages/b5/e8/dbf020b4d98251a9860752a094d09a65e1b436ad181faf929983f697048f/watchdog-6.0.0-py3-none-manylinux2014_x86_64.whl", hash = "sha256:20ffe5b202af80ab4266dcd3e91aae72bf2da48c0d33bdb15c66658e685e94e2", size = 79078 }, + { url = "https://files.pythonhosted.org/packages/07/f6/d0e5b343768e8bcb4cda79f0f2f55051bf26177ecd5651f84c07567461cf/watchdog-6.0.0-py3-none-win32.whl", hash = "sha256:07df1fdd701c5d4c8e55ef6cf55b8f0120fe1aef7ef39a1c6fc6bc2e606d517a", size = 79065 }, + { url = "https://files.pythonhosted.org/packages/db/d9/c495884c6e548fce18a8f40568ff120bc3a4b7b99813081c8ac0c936fa64/watchdog-6.0.0-py3-none-win_amd64.whl", hash = "sha256:cbafb470cf848d93b5d013e2ecb245d4aa1c8fd0504e863ccefa32445359d680", size = 79070 }, + { url = "https://files.pythonhosted.org/packages/33/e8/e40370e6d74ddba47f002a32919d91310d6074130fe4e17dabcafc15cbf1/watchdog-6.0.0-py3-none-win_ia64.whl", hash = "sha256:a1914259fa9e1454315171103c6a30961236f508b9b623eae470268bbcc6a22f", size = 79067 }, ] [[package]] @@ -5107,48 +5107,48 @@ wheels = [ [[package]] name = "yarl" -version = "1.16.0" +version = "1.17.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "idna" }, { name = "multidict" }, { name = "propcache" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/23/52/e9766cc6c2eab7dd1e9749c52c9879317500b46fb97d4105223f86679f93/yarl-1.16.0.tar.gz", hash = "sha256:b6f687ced5510a9a2474bbae96a4352e5ace5fa34dc44a217b0537fec1db00b4", size = 176548 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/0a/00/b29affe83de95e403f8a2a669b5a33f1e7dfe686264008100052eb0b05fd/yarl-1.16.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d8643975a0080f361639787415a038bfc32d29208a4bf6b783ab3075a20b1ef3", size = 140120 }, - { url = "https://files.pythonhosted.org/packages/3f/22/bcc9799950281a5d4f646536854839ccdbb965e900827ef0750680f81faf/yarl-1.16.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:676d96bafc8c2d0039cea0cd3fd44cee7aa88b8185551a2bb93354668e8315c2", size = 92956 }, - { url = "https://files.pythonhosted.org/packages/33/0f/1b76d853d9d921d68bd9991648be17d34e7ac51e2e20e7658f8ee7e2e2ad/yarl-1.16.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d9525f03269e64310416dbe6c68d3b23e5d34aaa8f47193a1c45ac568cecbc49", size = 90891 }, - { url = "https://files.pythonhosted.org/packages/61/19/3666d990c24aae98c748e2c262adc9b3a71e38834df007ac5317f4bbd789/yarl-1.16.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8b37d5ec034e668b22cf0ce1074d6c21fd2a08b90d11b1b73139b750a8b0dd97", size = 338857 }, - { url = "https://files.pythonhosted.org/packages/a0/3d/54acbb3cdfcfea03d6a3535cff1e060a2de23e419a4e3955c9661171b8a8/yarl-1.16.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4f32c4cb7386b41936894685f6e093c8dfaf0960124d91fe0ec29fe439e201d0", size = 354005 }, - { url = "https://files.pythonhosted.org/packages/15/98/cd9fe3938422c88775c94578a6c145aca89ff8368ff64e6032213ac12403/yarl-1.16.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5b8e265a0545637492a7e12fd7038370d66c9375a61d88c5567d0e044ded9202", size = 351195 }, - { url = "https://files.pythonhosted.org/packages/e2/13/b6eff6ea1667aee948ecd6b1c8fb6473234f8e48f49af97be93251869c51/yarl-1.16.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:789a3423f28a5fff46fbd04e339863c169ece97c827b44de16e1a7a42bc915d2", size = 342789 }, - { url = "https://files.pythonhosted.org/packages/fe/05/d98e65ea74a7e44bb033b2cf5bcc16edc1d5212bdc5ca7fbb5e380d89f8e/yarl-1.16.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f1d1f45e3e8d37c804dca99ab3cf4ab3ed2e7a62cd82542924b14c0a4f46d243", size = 336478 }, - { url = "https://files.pythonhosted.org/packages/7d/47/43de2e94b75f36d84733a35c807d0e33aaf084e98f32e2cbc685102f4ba4/yarl-1.16.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:621280719c4c5dad4c1391160a9b88925bb8b0ff6a7d5af3224643024871675f", size = 346008 }, - { url = "https://files.pythonhosted.org/packages/e2/de/9c2f900ec5e2f2e20329cfe7dcd9452e326d08cb5ecd098c2d4e9987b65c/yarl-1.16.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:ed097b26f18a1f5ff05f661dc36528c5f6735ba4ce8c9645e83b064665131349", size = 343745 }, - { url = "https://files.pythonhosted.org/packages/56/cd/b014dce22e37b77caa37f998c6c47434fd78d01e7be07119629f369f5ee1/yarl-1.16.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:2f1fe2b2e3ee418862f5ebc0c0083c97f6f6625781382f828f6d4e9b614eba9b", size = 349705 }, - { url = "https://files.pythonhosted.org/packages/07/17/bb191a26f7189423964e008ccb5146ce5258454ef3979f9d4c6860d282c7/yarl-1.16.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:87dd10bc0618991c66cee0cc65fa74a45f4ecb13bceec3c62d78ad2e42b27a16", size = 360767 }, - { url = "https://files.pythonhosted.org/packages/19/09/7d777369e151991b708a5b35280ea7444621d65af5f0545bcdce5d840867/yarl-1.16.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:4199db024b58a8abb2cfcedac7b1292c3ad421684571aeb622a02f242280e8d6", size = 364755 }, - { url = "https://files.pythonhosted.org/packages/00/32/7558997d1d2e53dab15f6db5db49fc6b412b63ede3cb8314e5dd7cff14fe/yarl-1.16.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:99a9dcd4b71dd5f5f949737ab3f356cfc058c709b4f49833aeffedc2652dac56", size = 357087 }, - { url = "https://files.pythonhosted.org/packages/28/20/c49a95a30c57224e5fb0fc83235295684b041300ce508b71821cb042527d/yarl-1.16.0-cp311-cp311-win32.whl", hash = "sha256:a9394c65ae0ed95679717d391c862dece9afacd8fa311683fc8b4362ce8a410c", size = 83030 }, - { url = "https://files.pythonhosted.org/packages/75/e3/2a746721d6f32886d9bafccdb80174349f180ccae0a287f25ba4312a2618/yarl-1.16.0-cp311-cp311-win_amd64.whl", hash = "sha256:5b9101f528ae0f8f65ac9d64dda2bb0627de8a50344b2f582779f32fda747c1d", size = 89616 }, - { url = "https://files.pythonhosted.org/packages/3a/be/82f696c8ce0395c37f62b955202368086e5cc114d5bb9cb1b634cff5e01d/yarl-1.16.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:4ffb7c129707dd76ced0a4a4128ff452cecf0b0e929f2668ea05a371d9e5c104", size = 141230 }, - { url = "https://files.pythonhosted.org/packages/38/60/45caaa748b53c4b0964f899879fcddc41faa4e0d12c6f0ae3311e8c151ff/yarl-1.16.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:1a5e9d8ce1185723419c487758d81ac2bde693711947032cce600ca7c9cda7d6", size = 93515 }, - { url = "https://files.pythonhosted.org/packages/54/bd/33aaca2f824dc1d630729e16e313797e8b24c8f7b6803307e5394274e443/yarl-1.16.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d743e3118b2640cef7768ea955378c3536482d95550222f908f392167fe62059", size = 91441 }, - { url = "https://files.pythonhosted.org/packages/af/fa/1ce8ca85489925aabdb8d2e7bbeaf74e7d3e6ac069779d6d6b9c7c62a8ed/yarl-1.16.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:26768342f256e6e3c37533bf9433f5f15f3e59e3c14b2409098291b3efaceacb", size = 330871 }, - { url = "https://files.pythonhosted.org/packages/f1/2a/a8110a225e498b87315827f8b61d24de35f86041834cf8c9c5544380c46b/yarl-1.16.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d1b0796168b953bca6600c5f97f5ed407479889a36ad7d17183366260f29a6b9", size = 340641 }, - { url = "https://files.pythonhosted.org/packages/d0/64/20cd1cb1f60b3ff49e7d75c1a2083352e7c5939368aafa960712c9e53797/yarl-1.16.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:858728086914f3a407aa7979cab743bbda1fe2bdf39ffcd991469a370dd7414d", size = 340245 }, - { url = "https://files.pythonhosted.org/packages/77/a8/7f38bbefb22eb925a68ad1d8193b05f51515614a6c0ebcadf26e9ae5e5ad/yarl-1.16.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5570e6d47bcb03215baf4c9ad7bf7c013e56285d9d35013541f9ac2b372593e7", size = 336054 }, - { url = "https://files.pythonhosted.org/packages/b4/a6/ac633ea3ea0c4eb1057e6800db1d077e77493b4b3449a4a97b2fbefadef4/yarl-1.16.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:66ea8311422a7ba1fc79b4c42c2baa10566469fe5a78500d4e7754d6e6db8724", size = 324405 }, - { url = "https://files.pythonhosted.org/packages/93/cd/4fc87ce9b0df7afb610ffb904f4aef25f59e0ad40a49da19a475facf98b7/yarl-1.16.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:649bddcedee692ee8a9b7b6e38582cb4062dc4253de9711568e5620d8707c2a3", size = 342235 }, - { url = "https://files.pythonhosted.org/packages/9f/bc/38bae4b716da1206849d88e167d3d2c5695ae9b418a3915220947593e5ca/yarl-1.16.0-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:3a91654adb7643cb21b46f04244c5a315a440dcad63213033826549fa2435f71", size = 340835 }, - { url = "https://files.pythonhosted.org/packages/dc/0f/b9efbc0075916a450cbad41299dff3bdd3393cb1d8378bb831c4a6a836e1/yarl-1.16.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:b439cae82034ade094526a8f692b9a2b5ee936452de5e4c5f0f6c48df23f8604", size = 344323 }, - { url = "https://files.pythonhosted.org/packages/87/6d/dc483ea1574005f14ef4c5f5f726cf60327b07ac83bd417d98db23e5285f/yarl-1.16.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:571f781ae8ac463ce30bacebfaef2c6581543776d5970b2372fbe31d7bf31a07", size = 355112 }, - { url = "https://files.pythonhosted.org/packages/10/22/3b7c3728d26b3cc295c51160ae4e2612ab7d3f9df30beece44bf72861730/yarl-1.16.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:aa7943f04f36d6cafc0cf53ea89824ac2c37acbdb4b316a654176ab8ffd0f968", size = 361506 }, - { url = "https://files.pythonhosted.org/packages/ad/8d/b7b5d43cf22a020b564ddf7502d83df150d797e34f18f6bf5fe0f12cbd91/yarl-1.16.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1a5cf32539373ff39d97723e39a9283a7277cbf1224f7aef0c56c9598b6486c3", size = 355746 }, - { url = "https://files.pythonhosted.org/packages/d9/a6/a2098bf3f09d38eb540b2b192e180d9d41c2ff64b692783db2188f0a55e3/yarl-1.16.0-cp312-cp312-win32.whl", hash = "sha256:a5b6c09b9b4253d6a208b0f4a2f9206e511ec68dce9198e0fbec4f160137aa67", size = 82675 }, - { url = "https://files.pythonhosted.org/packages/ed/a6/0a54b382cfc336e772b72681d6816a99222dc2d21876e649474973b8d244/yarl-1.16.0-cp312-cp312-win_amd64.whl", hash = "sha256:1208ca14eed2fda324042adf8d6c0adf4a31522fa95e0929027cd487875f0240", size = 88986 }, - { url = "https://files.pythonhosted.org/packages/fb/f7/87a32867ddc1a9817018bfd6109ee57646a543acf0d272843d8393e575f9/yarl-1.16.0-py3-none-any.whl", hash = "sha256:e6980a558d8461230c457218bd6c92dfc1d10205548215c2c21d79dc8d0a96f3", size = 43746 }, +sdist = { url = "https://files.pythonhosted.org/packages/54/9c/9c0a9bfa683fc1be7fdcd9687635151544d992cccd48892dc5e0a5885a29/yarl-1.17.1.tar.gz", hash = "sha256:067a63fcfda82da6b198fa73079b1ca40b7c9b7994995b6ee38acda728b64d47", size = 178163 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/ec/0f/ce6a2c8aab9946446fb27f1e28f0fd89ce84ae913ab18a92d18078a1c7ed/yarl-1.17.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:cbad927ea8ed814622305d842c93412cb47bd39a496ed0f96bfd42b922b4a217", size = 140727 }, + { url = "https://files.pythonhosted.org/packages/9d/df/204f7a502bdc3973cd9fc29e7dfad18ae48b3acafdaaf1ae07c0f41025aa/yarl-1.17.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:fca4b4307ebe9c3ec77a084da3a9d1999d164693d16492ca2b64594340999988", size = 93560 }, + { url = "https://files.pythonhosted.org/packages/a2/e1/f4d522ae0560c91a4ea31113a50f00f85083be885e1092fc6e74eb43cb1d/yarl-1.17.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ff5c6771c7e3511a06555afa317879b7db8d640137ba55d6ab0d0c50425cab75", size = 91497 }, + { url = "https://files.pythonhosted.org/packages/f1/82/783d97bf4a226f1a2e59b1966f2752244c2bf4dc89bc36f61d597b8e34e5/yarl-1.17.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5b29beab10211a746f9846baa39275e80034e065460d99eb51e45c9a9495bcca", size = 339446 }, + { url = "https://files.pythonhosted.org/packages/e5/ff/615600647048d81289c80907165de713fbc566d1e024789863a2f6563ba3/yarl-1.17.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1a52a1ffdd824fb1835272e125385c32fd8b17fbdefeedcb4d543cc23b332d74", size = 354616 }, + { url = "https://files.pythonhosted.org/packages/a5/04/bfb7adb452bd19dfe0c35354ffce8ebc3086e028e5f8270e409d17da5466/yarl-1.17.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:58c8e9620eb82a189c6c40cb6b59b4e35b2ee68b1f2afa6597732a2b467d7e8f", size = 351801 }, + { url = "https://files.pythonhosted.org/packages/10/e0/efe21edacdc4a638ce911f8cabf1c77cac3f60e9819ba7d891b9ceb6e1d4/yarl-1.17.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d216e5d9b8749563c7f2c6f7a0831057ec844c68b4c11cb10fc62d4fd373c26d", size = 343381 }, + { url = "https://files.pythonhosted.org/packages/63/f9/7bc7e69857d6fc3920ecd173592f921d5701f4a0dd3f2ae293b386cfa3bf/yarl-1.17.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:881764d610e3269964fc4bb3c19bb6fce55422828e152b885609ec176b41cf11", size = 337093 }, + { url = "https://files.pythonhosted.org/packages/93/52/99da61947466275ff17d7bc04b0ac31dfb7ec699bd8d8985dffc34c3a913/yarl-1.17.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:8c79e9d7e3d8a32d4824250a9c6401194fb4c2ad9a0cec8f6a96e09a582c2cc0", size = 346619 }, + { url = "https://files.pythonhosted.org/packages/91/8a/8aaad86a35a16e485ba0e5de0d2ae55bf8dd0c9f1cccac12be4c91366b1d/yarl-1.17.1-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:299f11b44d8d3a588234adbe01112126010bd96d9139c3ba7b3badd9829261c3", size = 344347 }, + { url = "https://files.pythonhosted.org/packages/af/b6/97f29f626b4a1768ffc4b9b489533612cfcb8905c90f745aade7b2eaf75e/yarl-1.17.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:cc7d768260f4ba4ea01741c1b5fe3d3a6c70eb91c87f4c8761bbcce5181beafe", size = 350316 }, + { url = "https://files.pythonhosted.org/packages/d7/98/8e0e8b812479569bdc34d66dd3e2471176ca33be4ff5c272a01333c4b269/yarl-1.17.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:de599af166970d6a61accde358ec9ded821234cbbc8c6413acfec06056b8e860", size = 361336 }, + { url = "https://files.pythonhosted.org/packages/9e/d3/d1507efa0a85c25285f8eb51df9afa1ba1b6e446dda781d074d775b6a9af/yarl-1.17.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:2b24ec55fad43e476905eceaf14f41f6478780b870eda5d08b4d6de9a60b65b4", size = 365350 }, + { url = "https://files.pythonhosted.org/packages/22/ba/ee7f1830449c96bae6f33210b7d89e8aaf3079fbdaf78ac398e50a9da404/yarl-1.17.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:9fb815155aac6bfa8d86184079652c9715c812d506b22cfa369196ef4e99d1b4", size = 357689 }, + { url = "https://files.pythonhosted.org/packages/a0/85/321c563dc5afe1661108831b965c512d185c61785400f5606006507d2e18/yarl-1.17.1-cp311-cp311-win32.whl", hash = "sha256:7615058aabad54416ddac99ade09a5510cf77039a3b903e94e8922f25ed203d7", size = 83635 }, + { url = "https://files.pythonhosted.org/packages/bc/da/543a32c00860588ff1235315b68f858cea30769099c32cd22b7bb266411b/yarl-1.17.1-cp311-cp311-win_amd64.whl", hash = "sha256:14bc88baa44e1f84164a392827b5defb4fa8e56b93fecac3d15315e7c8e5d8b3", size = 90218 }, + { url = "https://files.pythonhosted.org/packages/5d/af/e25615c7920396219b943b9ff8b34636ae3e1ad30777649371317d7f05f8/yarl-1.17.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:327828786da2006085a4d1feb2594de6f6d26f8af48b81eb1ae950c788d97f61", size = 141839 }, + { url = "https://files.pythonhosted.org/packages/83/5e/363d9de3495c7c66592523f05d21576a811015579e0c87dd38c7b5788afd/yarl-1.17.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:cc353841428d56b683a123a813e6a686e07026d6b1c5757970a877195f880c2d", size = 94125 }, + { url = "https://files.pythonhosted.org/packages/e3/a2/b65447626227ebe36f18f63ac551790068bf42c69bb22dfa3ae986170728/yarl-1.17.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:c73df5b6e8fabe2ddb74876fb82d9dd44cbace0ca12e8861ce9155ad3c886139", size = 92048 }, + { url = "https://files.pythonhosted.org/packages/a1/f5/2ef86458446f85cde10582054fd5113495ef8ce8477da35aaaf26d2970ef/yarl-1.17.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0bdff5e0995522706c53078f531fb586f56de9c4c81c243865dd5c66c132c3b5", size = 331472 }, + { url = "https://files.pythonhosted.org/packages/f3/6b/1ba79758ba352cdf2ad4c20cab1b982dd369aa595bb0d7601fc89bf82bee/yarl-1.17.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:06157fb3c58f2736a5e47c8fcbe1afc8b5de6fb28b14d25574af9e62150fcaac", size = 341260 }, + { url = "https://files.pythonhosted.org/packages/2d/41/4e07c2afca3f9ed3da5b0e38d43d0280d9b624a3d5c478c425e5ce17775c/yarl-1.17.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1654ec814b18be1af2c857aa9000de7a601400bd4c9ca24629b18486c2e35463", size = 340882 }, + { url = "https://files.pythonhosted.org/packages/c3/c0/cd8e94618983c1b811af082e1a7ad7764edb3a6af2bc6b468e0e686238ba/yarl-1.17.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7f6595c852ca544aaeeb32d357e62c9c780eac69dcd34e40cae7b55bc4fb1147", size = 336648 }, + { url = "https://files.pythonhosted.org/packages/ac/fc/73ec4340d391ffbb8f34eb4c55429784ec9f5bd37973ce86d52d67135418/yarl-1.17.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:459e81c2fb920b5f5df744262d1498ec2c8081acdcfe18181da44c50f51312f7", size = 325019 }, + { url = "https://files.pythonhosted.org/packages/57/48/da3ebf418fc239d0a156b3bdec6b17a5446f8d2dea752299c6e47b143a85/yarl-1.17.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:7e48cdb8226644e2fbd0bdb0a0f87906a3db07087f4de77a1b1b1ccfd9e93685", size = 342841 }, + { url = "https://files.pythonhosted.org/packages/5d/79/107272745a470a8167924e353a5312eb52b5a9bb58e22686adc46c94f7ec/yarl-1.17.1-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:d9b6b28a57feb51605d6ae5e61a9044a31742db557a3b851a74c13bc61de5172", size = 341433 }, + { url = "https://files.pythonhosted.org/packages/30/9c/6459668b3b8dcc11cd061fc53e12737e740fb6b1575b49c84cbffb387b3a/yarl-1.17.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:e594b22688d5747b06e957f1ef822060cb5cb35b493066e33ceac0cf882188b7", size = 344927 }, + { url = "https://files.pythonhosted.org/packages/c5/0b/93a17ed733aca8164fc3a01cb7d47b3f08854ce4f957cce67a6afdb388a0/yarl-1.17.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:5f236cb5999ccd23a0ab1bd219cfe0ee3e1c1b65aaf6dd3320e972f7ec3a39da", size = 355732 }, + { url = "https://files.pythonhosted.org/packages/9a/63/ead2ed6aec3c59397e135cadc66572330325a0c24cd353cd5c94f5e63463/yarl-1.17.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:a2a64e62c7a0edd07c1c917b0586655f3362d2c2d37d474db1a509efb96fea1c", size = 362123 }, + { url = "https://files.pythonhosted.org/packages/89/bf/f6b75b4c2fcf0e7bb56edc0ed74e33f37fac45dc40e5a52a3be66b02587a/yarl-1.17.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:d0eea830b591dbc68e030c86a9569826145df485b2b4554874b07fea1275a199", size = 356355 }, + { url = "https://files.pythonhosted.org/packages/45/1f/50a0257cd07eef65c8c65ad6a21f5fb230012d659e021aeb6ac8a7897bf6/yarl-1.17.1-cp312-cp312-win32.whl", hash = "sha256:46ddf6e0b975cd680eb83318aa1d321cb2bf8d288d50f1754526230fcf59ba96", size = 83279 }, + { url = "https://files.pythonhosted.org/packages/bc/82/fafb2c1268d63d54ec08b3a254fbe51f4ef098211501df646026717abee3/yarl-1.17.1-cp312-cp312-win_amd64.whl", hash = "sha256:117ed8b3732528a1e41af3aa6d4e08483c2f0f2e3d3d7dca7cf538b3516d93df", size = 89590 }, + { url = "https://files.pythonhosted.org/packages/52/ad/1fe7ff5f3e8869d4c5070f47b96bac2b4d15e67c100a8278d8e7876329fc/yarl-1.17.1-py3-none-any.whl", hash = "sha256:f1790a4b1e8e8e028c391175433b9c8122c39b46e1663228158e61e6f915bf06", size = 44352 }, ] [[package]]