diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml index 45a8af0aaf6e61..9e9f6af61d1011 100644 --- a/.github/ISSUE_TEMPLATE/config.yml +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -1,14 +1,11 @@ blank_issues_enabled: false contact_links: + - name: Join the Discord + url: https://discord.comma.ai + about: The community Discord is for both openpilot development and experience discussion - name: Report model bugs - url: https://github.com/commaai/openpilot/discussions/categories/model-feedback - about: Provide feedback for the driving or driver monitoring models - - name: Discussions - url: https://github.com/commaai/openpilot/discussions - about: For questions and general discussion about openpilot + url: https://discord.com/channels/469524606043160576/1254834193066623017 + about: Feedback for the driving and driver monitoring models goes in the #driving-feedback in Discord - name: Community Wiki url: https://github.com/commaai/openpilot/wiki about: Check out our community wiki - - name: Community Discord - url: https://discord.comma.ai - about: Check out our community discord diff --git a/.github/PULL_REQUEST_TEMPLATE/car_port.md b/.github/PULL_REQUEST_TEMPLATE/car_port.md index c7aa2b96c25a06..c1581d20559d65 100644 --- a/.github/PULL_REQUEST_TEMPLATE/car_port.md +++ b/.github/PULL_REQUEST_TEMPLATE/car_port.md @@ -8,7 +8,7 @@ assignees: '' **Checklist** -- [ ] added entry to CAR in selfdrive/car/*/values.py and ran `selfdrive/car/docs.py` to generate new docs +- [ ] added entry to CAR in selfdrive/car/*/values.py and ran `selfdrive/opcar/docs.py` to generate new docs - [ ] test route added to [routes.py](https://github.com/commaai/openpilot/blob/master/selfdrive/car/tests/routes.py) - [ ] route with openpilot: - [ ] route with stock system: diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index 2b4a5ed48f1b14..9e0c54218e24ea 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -44,7 +44,7 @@ Explain how you tested this bug fix. **Checklist** -- [ ] added entry to CAR in selfdrive/car/*/values.py and ran `selfdrive/car/docs.py` to generate new docs +- [ ] added entry to CAR in selfdrive/car/*/values.py and ran `selfdrive/opcar/docs.py` to generate new docs - [ ] test route added to [routes.py](https://github.com/commaai/openpilot/blob/master/selfdrive/car/tests/routes.py) - [ ] route with openpilot: - [ ] route with stock system: diff --git a/.github/workflows/badges.yaml b/.github/workflows/badges.yaml index f8d2fc3cf10bd4..63ee736dcab84b 100644 --- a/.github/workflows/badges.yaml +++ b/.github/workflows/badges.yaml @@ -23,7 +23,7 @@ jobs: - uses: ./.github/workflows/setup-with-retry - name: Push badges run: | - ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/ui/translations/create_badges.py" + ${{ env.RUN }} "scons -j$(nproc) && python3 selfdrive/ui/translations/create_badges.py" rm .gitattributes diff --git a/.github/workflows/repo-maintenance.yaml b/.github/workflows/repo-maintenance.yaml index 3893c7fa5e0bc1..78f64c03b1040b 100644 --- a/.github/workflows/repo-maintenance.yaml +++ b/.github/workflows/repo-maintenance.yaml @@ -6,33 +6,6 @@ on: workflow_dispatch: jobs: - bump_submodules: - name: bump_submodules - runs-on: ubuntu-latest - container: - image: ghcr.io/commaai/openpilot-base:latest - if: github.repository == 'commaai/openpilot' - steps: - - uses: actions/checkout@v4 - with: - submodules: true - - name: bump submodules - run: | - git config --global --add safe.directory '*' - git -c submodule."tinygrad".update=none submodule update --remote - git add . - - name: Create Pull Request - uses: peter-evans/create-pull-request@9153d834b60caba6d51c9b9510b087acf9f33f83 - with: - author: Vehicle Researcher - token: ${{ secrets.ACTIONS_CREATE_PR_PAT }} - commit-message: bump submodules - title: '[bot] Bump submodules' - branch: auto-bump-submodules - base: master - delete-branch: true - body: 'Automatic PR from repo-maintenance -> bump_submodules' - labels: bot package_updates: name: package_updates runs-on: ubuntu-latest @@ -41,11 +14,18 @@ jobs: if: github.repository == 'commaai/openpilot' steps: - uses: actions/checkout@v4 + with: + submodules: true - name: uv lock run: | python3 -m ensurepip --upgrade pip3 install uv uv lock --upgrade + - name: bump submodules + run: | + git config --global --add safe.directory '*' + git -c submodule."tinygrad".update=none submodule update --remote + git add . - name: Create Pull Request uses: peter-evans/create-pull-request@9153d834b60caba6d51c9b9510b087acf9f33f83 with: diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 10444109589746..3b8f9a43332215 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -54,7 +54,7 @@ jobs: timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 10 || 30) }} # allow more time when we missed the scons cache run: | cd $STRIPPED_DIR - ${{ env.RUN }} "python system/manager/build.py" + ${{ env.RUN }} "python3 system/manager/build.py" - name: Run tests timeout-minutes: 3 run: | @@ -67,7 +67,7 @@ jobs: cd $GITHUB_WORKSPACE cp pyproject.toml $STRIPPED_DIR cd $STRIPPED_DIR - ${{ env.RUN }} "scripts/lint.sh --skip check_added_large_files" + ${{ env.RUN }} "scripts/lint/lint.sh --skip check_added_large_files" build: strategy: @@ -221,7 +221,7 @@ jobs: - name: Upload reference logs if: ${{ failure() && steps.print-diff.outcome == 'success' && github.repository == 'commaai/openpilot' && env.AZURE_TOKEN != '' }} run: | - ${{ env.RUN }} "unset PYTHONWARNINGS && AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only" + ${{ env.RUN }} "unset PYTHONWARNINGS && AZURE_TOKEN='$AZURE_TOKEN' python3 selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only" # PYTHONWARNINGS triggers a SyntaxError in onnxruntime - name: Run model replay with ONNX timeout-minutes: 4 @@ -291,7 +291,7 @@ jobs: - uses: ./.github/workflows/setup-with-retry - name: Get base car info run: | - ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/debug/dump_car_docs.py --path /tmp/openpilot_cache/base_car_docs" + ${{ env.RUN }} "scons -j$(nproc) && python3 selfdrive/debug/dump_car_docs.py --path /tmp/openpilot_cache/base_car_docs" sudo chown -R $USER:$USER ${{ github.workspace }} - uses: actions/checkout@v4 with: @@ -303,7 +303,7 @@ jobs: run: | cd current ${{ env.RUN }} "scons -j$(nproc)" - output=$(${{ env.RUN }} "python selfdrive/debug/print_docs_diff.py --path /tmp/openpilot_cache/base_car_docs") + output=$(${{ env.RUN }} "python3 selfdrive/debug/print_docs_diff.py --path /tmp/openpilot_cache/base_car_docs") output="${output//$'\n'/'%0A'}" echo "::set-output name=diff::$output" - name: Find comment @@ -348,7 +348,7 @@ jobs: run: > ${{ env.RUN }} "PYTHONWARNINGS=ignore && source selfdrive/test/setup_xvfb.sh && - python selfdrive/ui/tests/test_ui/run.py" + python3 selfdrive/ui/tests/test_ui/run.py" - name: Upload Test Report uses: actions/upload-artifact@v4 with: diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index bc19e237780058..c678abb27644d4 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -6,6 +6,7 @@ on: - 'master' paths: - 'selfdrive/ui/**' + workflow_dispatch: env: UI_JOB_NAME: "Create UI Report" @@ -78,11 +79,10 @@ jobs: - + - diff --git a/.importlinter b/.importlinter deleted file mode 100644 index 087035ca9e39b4..00000000000000 --- a/.importlinter +++ /dev/null @@ -1,65 +0,0 @@ -[importlinter] -root_packages = - openpilot - -[importlinter:contract:1] -name = Forbid imports from openpilot.selfdrive.car to openpilot.system -type = forbidden -source_modules = - openpilot.selfdrive.car -forbidden_modules = - openpilot.common - openpilot.selfdrive.controls - openpilot.selfdrive.debug - openpilot.selfdrive.pandad - openpilot.selfdrive.test - openpilot.system - openpilot.body - openpilot.tools - openpilot.docs - openpilot.msgq - openpilot.panda - openpilot.rednose - openpilot.release - openpilot.teleoprtc - openpilot.tinygrad -ignore_imports = - # remove these - openpilot.selfdrive.car.interfaces -> openpilot.selfdrive.controls.lib.events - openpilot.selfdrive.car.body.carcontroller -> openpilot.selfdrive.controls.lib.pid - openpilot.selfdrive.car.tests.test_docs -> openpilot.common.basedir - openpilot.selfdrive.car.docs -> openpilot.common.basedir - - # car interface will not filter the speed - openpilot.selfdrive.car.interfaces -> openpilot.common.simple_kalman - - openpilot.selfdrive.car.gm.interface -> openpilot.common.basedir - openpilot.selfdrive.car.interfaces -> openpilot.common.basedir - - # params will need to move to new openpilot files that just call car files - openpilot.selfdrive.car.fw_versions -> openpilot.common.params - openpilot.selfdrive.car.ecu_addrs -> openpilot.common.params - - # these are okay - openpilot.selfdrive.car.card -> openpilot.common.swaglog - openpilot.selfdrive.car.card -> openpilot.common.realtime - openpilot.selfdrive.car.card -> openpilot.selfdrive.controls.lib.events - openpilot.selfdrive.car.tests.test_models -> openpilot.tools.lib.logreader - openpilot.selfdrive.car.tests.test_models -> openpilot.selfdrive.car.card - openpilot.selfdrive.car.tests.test_models -> openpilot.tools.lib.route - openpilot.selfdrive.car.tests.test_models -> openpilot.system.hardware.hw - openpilot.selfdrive.car.tests.test_models -> openpilot.selfdrive.test.helpers - openpilot.selfdrive.car.tests.test_car_interfaces -> openpilot.selfdrive.controls.lib.latcontrol_angle - openpilot.selfdrive.car.tests.test_car_interfaces -> openpilot.selfdrive.controls.lib.longcontrol - openpilot.selfdrive.car.tests.test_car_interfaces -> openpilot.selfdrive.controls.lib.latcontrol_torque - openpilot.selfdrive.car.tests.test_car_interfaces -> openpilot.selfdrive.controls.lib.latcontrol_pid - openpilot.selfdrive.car.card -> openpilot.common.params - openpilot.selfdrive.car.tests.test_models -> openpilot.common.params - openpilot.selfdrive.car.tests.test_models -> openpilot.common.basedir - openpilot.selfdrive.car.card -> openpilot.selfdrive.pandad - openpilot.selfdrive.car.tests.test_docs -> openpilot.selfdrive.debug.dump_car_docs - openpilot.selfdrive.car.tests.test_docs -> openpilot.selfdrive.debug.print_docs_diff - openpilot.selfdrive.car.tests.test_car_interfaces -> openpilot.selfdrive.pandad - openpilot.selfdrive.car.tests.test_models -> openpilot.selfdrive.pandad - openpilot.selfdrive.car.tests.test_car_interfaces -> openpilot.selfdrive.test.fuzzy_generation -unmatched_ignore_imports_alerting = warn diff --git a/Jenkinsfile b/Jenkinsfile index d2dffeecc74a00..799b4fbbeb932e 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -95,42 +95,6 @@ def deviceStage(String stageName, String deviceType, List extra_env, def steps) } } -def pcStage(String stageName, Closure body) { - node { - stage(stageName) { - if (currentBuild.result != null) { - return - } - - checkout scm - - def dockerArgs = "--user=batman -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/scons_cache:/tmp/scons_cache -e PYTHONPATH=${env.WORKSPACE} --cpus=8 --memory 16g -e PYTEST_ADDOPTS='-n8'"; - - def openpilot_base = retryWithDelay (3, 15) { - return docker.build("openpilot-base:build-${env.GIT_COMMIT}", "-f Dockerfile.openpilot_base .") - } - - lock(resource: "", label: 'pc', inversePrecedence: true, quantity: 1) { - openpilot_base.inside(dockerArgs) { - timeout(time: 20, unit: 'MINUTES') { - try { - retryWithDelay (3, 15) { - sh "git config --global --add safe.directory '*'" - sh "git submodule update --init --recursive" - sh "git lfs pull" - } - body() - } finally { - sh "rm -rf ${env.WORKSPACE}/* || true" - sh "rm -rf .* || true" - } - } - } - } - } - } -} - def setupCredentials() { withCredentials([ string(credentialsId: 'azure_token', variable: 'AZURE_TOKEN'), diff --git a/cereal/car.capnp b/cereal/car.capnp index 3df23d99214ea2..cbfb330c22705f 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -196,6 +196,7 @@ struct CarState { accFaulted @42 :Bool; carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable espActive @51 :Bool; + vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. # cruise state cruiseState @10 :CruiseState; diff --git a/cereal/log.capnp b/cereal/log.capnp index dcf9463ac8bee9..3e9fd3b31185a7 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -2082,9 +2082,15 @@ struct LiveParametersData { stiffnessFactorStd @12 :Float32; steerRatioStd @13 :Float32; roll @14 :Float32; - filterState @15 :LiveLocationKalman.Measurement; + debugFilterState @16 :FilterState; yawRateDEPRECATED @7 :Float32; + filterStateDEPRECATED @15 :LiveLocationKalman.Measurement; + + struct FilterState { + value @0 : List(Float64); + std @1 : List(Float64); + } } struct LiveTorqueParametersData { diff --git a/common/mock/__init__.py b/common/mock/__init__.py index 8c86bbd394caee..4b01dfe8411b11 100644 --- a/common/mock/__init__.py +++ b/common/mock/__init__.py @@ -8,12 +8,12 @@ import threading from cereal.messaging import PubMaster from cereal.services import SERVICE_LIST -from openpilot.common.mock.generators import generate_liveLocationKalman +from openpilot.common.mock.generators import generate_livePose from openpilot.common.realtime import Ratekeeper MOCK_GENERATOR = { - "liveLocationKalman": generate_liveLocationKalman + "livePose": generate_livePose } diff --git a/common/mock/generators.py b/common/mock/generators.py index 40951faf8543bf..5cd9c88a56fc33 100644 --- a/common/mock/generators.py +++ b/common/mock/generators.py @@ -1,20 +1,14 @@ from cereal import messaging -LOCATION1 = (32.7174, -117.16277) -LOCATION2 = (32.7558, -117.2037) - -LLK_DECIMATION = 10 -RENDER_FRAMES = 15 -DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION - - -def generate_liveLocationKalman(location=LOCATION1): - msg = messaging.new_message('liveLocationKalman') - msg.liveLocationKalman.positionGeodetic = {'value': [*location, 0], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.positionECEF = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.calibratedOrientationNED = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.velocityCalibrated = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.status = 'valid' - msg.liveLocationKalman.gpsOK = True +def generate_livePose(): + msg = messaging.new_message('livePose') + meas = {'x': 0.0, 'y': 0.0, 'z': 0.0, 'xStd': 0.0, 'yStd': 0.0, 'zStd': 0.0, 'valid': True} + msg.livePose.orientationNED = meas + msg.livePose.velocityDevice = meas + msg.livePose.angularVelocityDevice = meas + msg.livePose.accelerationDevice = meas + msg.livePose.inputsOK = True + msg.livePose.posenetOK = True + msg.livePose.sensorsOK = True return msg diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 9256f463af7e17..442a811b160603 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash if [ -z "$BASEDIR" ]; then BASEDIR="/data/openpilot" diff --git a/launch_env.sh b/launch_env.sh index 81578aff0157e3..1e5bc7b607cc37 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash export OMP_NUM_THREADS=1 export MKL_NUM_THREADS=1 diff --git a/launch_openpilot.sh b/launch_openpilot.sh index 2888814c223499..d6e3424c348bf5 100755 --- a/launch_openpilot.sh +++ b/launch_openpilot.sh @@ -1,3 +1,3 @@ -#!/usr/bin/bash +#!/usr/bin/env bash exec ./launch_chffrplus.sh diff --git a/opendbc_repo b/opendbc_repo index 8978a288093846..5d8ad34aae1061 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 8978a28809384688c7638308c3f284d73c7cbbd0 +Subproject commit 5d8ad34aae106199f41d66780fe84a0701cb6e4b diff --git a/panda b/panda index 2448012cef6503..dde6af8e347d55 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 2448012cef65033dd945b2223e267a066ff19466 +Subproject commit dde6af8e347d55ab0d448ccb186a3169e01e6b27 diff --git a/pyproject.toml b/pyproject.toml index a0131773e8e0e9..df6ba3f7ccbcd4 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -74,7 +74,6 @@ docs = [ testing = [ "coverage", "hypothesis ==6.47.*", - "import-linter", "mypy", "pytest", "pytest-cov", @@ -100,7 +99,7 @@ dev = [ "inputs", "lru-dict", "matplotlib", - "metadrive-simulator@git+https://github.com/commaai/metadrive@opencv_headless ; platform_machine != 'aarch64'", + "metadrive-simulator@git+https://github.com/commaai/metadrive@main ; platform_machine != 'aarch64'", "parameterized >=0.8, <0.9", #"pprofile", "pyautogui", @@ -108,7 +107,7 @@ dev = [ "pytools < 2024.1.11; platform_machine != 'aarch64'", # pyopencl use a broken version "pywinctl", "pyprof2calltree", - "rerun-sdk", + "rerun-sdk >= 0.18", "tabulate", "types-requests", "types-tabulate", @@ -145,6 +144,7 @@ testpaths = [ "common", "selfdrive/pandad", "selfdrive/car", + "selfdrive/opcar", "selfdrive/controls", "selfdrive/locationd", "selfdrive/monitoring", diff --git a/release/build_devel.sh b/release/build_devel.sh index 7fce11ca729147..c6d04396fe397d 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -ex DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/release/build_release.sh b/release/build_release.sh index 510df75e514772..bcc4b5cdedd735 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e set -x diff --git a/release/check-dirty.sh b/release/check-dirty.sh index 9c6389f3801ac6..ac049970cf06bc 100755 --- a/release/check-dirty.sh +++ b/release/check-dirty.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/release/check-submodules.sh b/release/check-submodules.sh index 5305cecd3a3889..48850deaf8ea67 100755 --- a/release/check-submodules.sh +++ b/release/check-submodules.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash while read hash submodule ref; do git -C $submodule fetch --depth 3000 origin master diff --git a/release/release_files.py b/release/release_files.py index b3887e39e02539..998b248724f114 100755 --- a/release/release_files.py +++ b/release/release_files.py @@ -59,6 +59,53 @@ "tinygrad_repo/tinygrad/runtime/ops_gpu.py", "tinygrad_repo/tinygrad/shape/*", "tinygrad_repo/tinygrad/.*.py", + + # TODO: do this automatically + "opendbc_repo/dbc/comma_body.dbc", + "opendbc_repo/dbc/chrysler_ram_hd_generated.dbc", + "opendbc_repo/dbc/chrysler_ram_dt_generated.dbc", + "opendbc_repo/dbc/chrysler_pacifica_2017_hybrid_generated.dbc", + "opendbc_repo/dbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc", + "opendbc_repo/dbc/gm_global_a_powertrain_generated.dbc", + "opendbc_repo/dbc/gm_global_a_object.dbc", + "opendbc_repo/dbc/gm_global_a_chassis.dbc", + "opendbc_repo/dbc/FORD_CADS.dbc", + "opendbc_repo/dbc/ford_fusion_2018_adas.dbc", + "opendbc_repo/dbc/ford_lincoln_base_pt.dbc", + "opendbc_repo/dbc/honda_accord_2018_can_generated.dbc", + "opendbc_repo/dbc/acura_ilx_2016_can_generated.dbc", + "opendbc_repo/dbc/acura_rdx_2018_can_generated.dbc", + "opendbc_repo/dbc/acura_rdx_2020_can_generated.dbc", + "opendbc_repo/dbc/honda_civic_touring_2016_can_generated.dbc", + "opendbc_repo/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc", + "opendbc_repo/dbc/honda_crv_touring_2016_can_generated.dbc", + "opendbc_repo/dbc/honda_crv_ex_2017_can_generated.dbc", + "opendbc_repo/dbc/honda_crv_ex_2017_body_generated.dbc", + "opendbc_repo/dbc/honda_crv_executive_2016_can_generated.dbc", + "opendbc_repo/dbc/honda_fit_ex_2018_can_generated.dbc", + "opendbc_repo/dbc/honda_odyssey_exl_2018_generated.dbc", + "opendbc_repo/dbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc", + "opendbc_repo/dbc/honda_insight_ex_2019_can_generated.dbc", + "opendbc_repo/dbc/acura_ilx_2016_nidec.dbc", + "opendbc_repo/dbc/honda_civic_ex_2022_can_generated.dbc", + "opendbc_repo/dbc/hyundai_canfd.dbc", + "opendbc_repo/dbc/hyundai_kia_generic.dbc", + "opendbc_repo/dbc/hyundai_kia_mando_front_radar_generated.dbc", + "opendbc_repo/dbc/mazda_2017.dbc", + "opendbc_repo/dbc/nissan_x_trail_2017_generated.dbc", + "opendbc_repo/dbc/nissan_leaf_2018_generated.dbc", + "opendbc_repo/dbc/subaru_global_2017_generated.dbc", + "opendbc_repo/dbc/subaru_global_2020_hybrid_generated.dbc", + "opendbc_repo/dbc/subaru_outback_2015_generated.dbc", + "opendbc_repo/dbc/subaru_outback_2019_generated.dbc", + "opendbc_repo/dbc/subaru_forester_2017_generated.dbc", + "opendbc_repo/dbc/toyota_tnga_k_pt_generated.dbc", + "opendbc_repo/dbc/toyota_new_mc_pt_generated.dbc", + "opendbc_repo/dbc/toyota_nodsu_pt_generated.dbc", + "opendbc_repo/dbc/toyota_adas.dbc", + "opendbc_repo/dbc/toyota_tss2_adas.dbc", + "opendbc_repo/dbc/vw_golf_mk4.dbc", + "opendbc_repo/dbc/vw_mqb_2010.dbc", ] if __name__ == "__main__": diff --git a/scripts/apply-pr.sh b/scripts/apply-pr.sh index 74f765391a35de..ad0af46b49a9ac 100755 --- a/scripts/apply-pr.sh +++ b/scripts/apply-pr.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash if [ $# -eq 0 ]; then echo "usage: $0 " diff --git a/scripts/build_small.sh b/scripts/build_small.sh index 90f55373e249f2..176ca5aaa8f92a 100755 --- a/scripts/build_small.sh +++ b/scripts/build_small.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -ex DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/scripts/cell.sh b/scripts/cell.sh index 4ba007a532eae3..310a9694fd044b 100755 --- a/scripts/cell.sh +++ b/scripts/cell.sh @@ -1,3 +1,3 @@ -#!/usr/bin/bash +#!/usr/bin/env bash nmcli connection modify --temporary esim ipv4.route-metric 1 ipv6.route-metric 1 nmcli con up esim diff --git a/scripts/checkout-pr.sh b/scripts/checkout-pr.sh index 43f658befff302..eeba816d8898b5 100755 --- a/scripts/checkout-pr.sh +++ b/scripts/checkout-pr.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e if [ $# -eq 0 ]; then diff --git a/scripts/count_cars.py b/scripts/count_cars.py index 28057ddb04da3c..19f486735a7a58 100755 --- a/scripts/count_cars.py +++ b/scripts/count_cars.py @@ -2,7 +2,7 @@ from collections import Counter from pprint import pprint -from openpilot.selfdrive.car.docs import get_all_car_docs +from opendbc.car.docs import get_all_car_docs if __name__ == "__main__": cars = get_all_car_docs() diff --git a/scripts/git_rewrite/rewrite-git-history.sh b/scripts/git_rewrite/rewrite-git-history.sh index 5a97e6bbad0e72..cce4455ce5be13 100755 --- a/scripts/git_rewrite/rewrite-git-history.sh +++ b/scripts/git_rewrite/rewrite-git-history.sh @@ -1,4 +1,5 @@ -#!/bin/bash -e +#!/usr/bin/env bash +set -e SRC=/tmp/openpilot/ SRC_CLONE=/tmp/openpilot-clone/ @@ -209,7 +210,7 @@ if [ ! -f "$SRC_CLONE/rewrite-branches-done" ]; then MERGE_BASE=$(git merge-base master origin/$BRANCH) || true if [ -n "$MERGE_BASE" ]; then echo "Rewriting branch: $BRANCH" - + # create a new branch based on the new master NEW_MERGE_BASE=$(grep "^$MERGE_BASE " "commit-map.txt" | awk '{print $2}') if [ -z "$NEW_MERGE_BASE" ]; then @@ -217,10 +218,10 @@ if [ ! -f "$SRC_CLONE/rewrite-branches-done" ]; then continue fi git checkout -b ${BRANCH}_new $NEW_MERGE_BASE - + # get the range of commits unique to this branch COMMITS=$(git rev-list --reverse $MERGE_BASE..origin/${BRANCH}) - + HAS_ERROR=0 # simple delimiter @@ -263,7 +264,7 @@ if [ ! -f "$SRC_CLONE/rewrite-branches-done" ]; then git commit --amend -m "$(git log -1 --pretty=%B)" -m "Former-commit-id: $COMMIT" > /dev/null fi done - + # force push the new branch if [ $HAS_ERROR -eq 0 ]; then # git lfs goes haywire here, so we need to install and uninstall @@ -271,7 +272,7 @@ if [ ! -f "$SRC_CLONE/rewrite-branches-done" ]; then git lfs uninstall --local > /dev/null git push -f origin ${BRANCH}_new:${BRANCH} fi - + # clean up local branch git checkout master > /dev/null git branch -D ${BRANCH}_new > /dev/null @@ -318,7 +319,7 @@ if [ ! -f "$SRC_CLONE/validation-done" ]; then # echo -ne "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Comparing old commit $OLD_COMMIT_SHORT ($OLD_DATE) with new commit $NEW_COMMIT_SHORT ($NEW_DATE)"\\r echo "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Comparing old commit $OLD_COMMIT_SHORT ($OLD_DATE) with new commit $NEW_COMMIT_SHORT ($NEW_DATE)" - + # generate lists of files and their hashes for the old and new commits, excluding ignored files OLD_FILES=$(git ls-tree -r $OLD_COMMIT | grep -vE "$(IFS='|'; echo "${VALIDATE_IGNORE_FILES[*]}")") NEW_FILES=$(git ls-tree -r $NEW_COMMIT | grep -vE "$(IFS='|'; echo "${VALIDATE_IGNORE_FILES[*]}")") diff --git a/scripts/launch_corolla.sh b/scripts/launch_corolla.sh index 4e5bca6ce5e6d1..926569a1e0e13d 100755 --- a/scripts/launch_corolla.sh +++ b/scripts/launch_corolla.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/scripts/lint/check_shebang_format.sh b/scripts/lint/check_shebang_format.sh new file mode 100755 index 00000000000000..89b95d5929a3b2 --- /dev/null +++ b/scripts/lint/check_shebang_format.sh @@ -0,0 +1,15 @@ +#!/usr/bin/env bash + +FAIL=0 + +if grep '^#!.*python' $@ | grep -v '#!/usr/bin/env python3$'; then + echo -e "Invalid shebang! Must use '#!/usr/bin/env python3'\n" + FAIL=1 +fi + +if grep '^#!.*bash' $@ | grep -v '#!/usr/bin/env bash$'; then + echo -e "Invalid shebang! Must use '#!/usr/bin/env bash'" + FAIL=1 +fi + +exit $FAIL diff --git a/scripts/lint.sh b/scripts/lint/lint.sh similarity index 96% rename from scripts/lint.sh rename to scripts/lint/lint.sh index 2b6fd071859a3c..652fa4d65ff622 100755 --- a/scripts/lint.sh +++ b/scripts/lint/lint.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e RED='\033[0;31m' @@ -8,7 +8,7 @@ BOLD='\033[1m' NC='\033[0m' DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -cd $DIR/../ +cd $DIR/../../ FAILED=0 @@ -48,9 +48,9 @@ function run_tests() { PYTHON_FILES=$2 run "ruff" ruff check $PYTHON_FILES --quiet - run "lint-imports" lint-imports run "check_added_large_files" python3 -m pre_commit_hooks.check_added_large_files --enforce-all $ALL_FILES --maxkb=120 run "check_shebang_scripts_are_executable" python3 -m pre_commit_hooks.check_shebang_scripts_are_executable $ALL_FILES + run "check_shebang_format" $DIR/check_shebang_format.sh $ALL_FILES if [[ -z "$FAST" ]]; then run "mypy" mypy $PYTHON_FILES @@ -68,7 +68,6 @@ function help() { echo -e "${BOLD}${UNDERLINE}Tests:${NC}" echo -e " ${BOLD}ruff${NC}" echo -e " ${BOLD}mypy${NC}" - echo -e " ${BOLD}lint-imports${NC}" echo -e " ${BOLD}codespell${NC}" echo -e " ${BOLD}check_added_large_files${NC}" echo -e " ${BOLD}check_shebang_scripts_are_executable${NC}" diff --git a/scripts/retry.sh b/scripts/retry.sh index 4861748e557dbf..23501d75595954 100755 --- a/scripts/retry.sh +++ b/scripts/retry.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash function fail { echo $1 >&2 diff --git a/selfdrive/assets/compress-images.sh b/selfdrive/assets/compress-images.sh index a1a4f8bb40a4cf..de59099bd13398 100755 --- a/selfdrive/assets/compress-images.sh +++ b/selfdrive/assets/compress-images.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "compressing training guide images" optipng -o7 -strip all training/* diff --git a/selfdrive/assets/strip-svg-metadata.sh b/selfdrive/assets/strip-svg-metadata.sh index a8b35eadde300d..e51dc9481d73a1 100755 --- a/selfdrive/assets/strip-svg-metadata.sh +++ b/selfdrive/assets/strip-svg-metadata.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # sudo apt install scour diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 2c6a45d557b9f7..e69de29bb2d1d6 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -1,326 +0,0 @@ -# functions common among cars -import logging -from collections import namedtuple -from dataclasses import dataclass -from enum import IntFlag, ReprEnum, EnumType -from dataclasses import replace - -import capnp - -from cereal import car -from panda.python.uds import SERVICE_TYPE -from openpilot.selfdrive.car.can_definitions import CanData -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.helpers import clip, interp - -# set up logging -carlog = logging.getLogger('carlog') -carlog.setLevel(logging.INFO) -carlog.propagate = False - -DT_CTRL = 0.01 # car state and control loop timestep (s) - -# kg of standard extra cargo to count for drive, gas, etc... -STD_CARGO_KG = 136. - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -AngleRateLimit = namedtuple('AngleRateLimit', ['speed_bp', 'angle_v']) - - -def apply_hysteresis(val: float, val_steady: float, hyst_gap: float) -> float: - if val > val_steady + hyst_gap: - val_steady = val - hyst_gap - elif val < val_steady - hyst_gap: - val_steady = val + hyst_gap - return val_steady - - -def create_button_events(cur_btn: int, prev_btn: int, buttons_dict: dict[int, capnp.lib.capnp._EnumModule], - unpressed_btn: int = 0) -> list[capnp.lib.capnp._DynamicStructBuilder]: - events: list[capnp.lib.capnp._DynamicStructBuilder] = [] - - if cur_btn == prev_btn: - return events - - # Add events for button presses, multiple when a button switches without going to unpressed - for pressed, btn in ((False, prev_btn), (True, cur_btn)): - if btn != unpressed_btn: - events.append(car.CarState.ButtonEvent(pressed=pressed, - type=buttons_dict.get(btn, ButtonType.unknown))) - return events - - -def gen_empty_fingerprint(): - return {i: {} for i in range(8)} - - -# these params were derived for the Civic and used to calculate params for other cars -class VehicleDynamicsParams: - MASS = 1326. + STD_CARGO_KG - WHEELBASE = 2.70 - CENTER_TO_FRONT = WHEELBASE * 0.4 - CENTER_TO_REAR = WHEELBASE - CENTER_TO_FRONT - ROTATIONAL_INERTIA = 2500 - TIRE_STIFFNESS_FRONT = 192150 - TIRE_STIFFNESS_REAR = 202500 - - -# TODO: get actual value, for now starting with reasonable value for -# civic and scaling by mass and wheelbase -def scale_rot_inertia(mass, wheelbase): - return VehicleDynamicsParams.ROTATIONAL_INERTIA * mass * wheelbase ** 2 / (VehicleDynamicsParams.MASS * VehicleDynamicsParams.WHEELBASE ** 2) - - -# TODO: start from empirically derived lateral slip stiffness for the civic and scale by -# mass and CG position, so all cars will have approximately similar dyn behaviors -def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor): - center_to_rear = wheelbase - center_to_front - tire_stiffness_front = (VehicleDynamicsParams.TIRE_STIFFNESS_FRONT * tire_stiffness_factor) * mass / VehicleDynamicsParams.MASS * \ - (center_to_rear / wheelbase) / (VehicleDynamicsParams.CENTER_TO_REAR / VehicleDynamicsParams.WHEELBASE) - - tire_stiffness_rear = (VehicleDynamicsParams.TIRE_STIFFNESS_REAR * tire_stiffness_factor) * mass / VehicleDynamicsParams.MASS * \ - (center_to_front / wheelbase) / (VehicleDynamicsParams.CENTER_TO_FRONT / VehicleDynamicsParams.WHEELBASE) - - return tire_stiffness_front, tire_stiffness_rear - - -DbcDict = dict[str, str] - - -def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None) -> DbcDict: - return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc} - - -def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): - - # limits due to driver torque - driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER - driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER - max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0) - min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0) - apply_torque = clip(apply_torque, min_steer_allowed, max_steer_allowed) - - # slow rate if steer torque increases in magnitude - if apply_torque_last > 0: - apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), - apply_torque_last + LIMITS.STEER_DELTA_UP) - else: - apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP, - min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) - - return int(round(float(apply_torque))) - - -def apply_dist_to_meas_limits(val, val_last, val_meas, - STEER_DELTA_UP, STEER_DELTA_DOWN, - STEER_ERROR_MAX, STEER_MAX): - # limits due to comparison of commanded val VS measured val (torque/angle/curvature) - max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX) - min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX) - - val = clip(val, min_lim, max_lim) - - # slow rate if val increases in magnitude - if val_last > 0: - val = clip(val, - max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP), - val_last + STEER_DELTA_UP) - else: - val = clip(val, - val_last - STEER_DELTA_UP, - min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP)) - - return float(val) - - -def apply_meas_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS): - return int(round(apply_dist_to_meas_limits(apply_torque, apply_torque_last, motor_torque, - LIMITS.STEER_DELTA_UP, LIMITS.STEER_DELTA_DOWN, - LIMITS.STEER_ERROR_MAX, LIMITS.STEER_MAX))) - - -def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS): - # pick angle rate limits based on wind up/down - steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last) - rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN - - angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v) - return clip(apply_angle, apply_angle_last - angle_rate_lim, apply_angle_last + angle_rate_lim) - - -def common_fault_avoidance(fault_condition: bool, request: bool, above_limit_frames: int, - max_above_limit_frames: int, max_mismatching_frames: int = 1): - """ - Several cars have the ability to work around their EPS limits by cutting the - request bit of their LKAS message after a certain number of frames above the limit. - """ - - # Count up to max_above_limit_frames, at which point we need to cut the request for above_limit_frames to avoid a fault - if request and fault_condition: - above_limit_frames += 1 - else: - above_limit_frames = 0 - - # Once we cut the request bit, count additionally to max_mismatching_frames before setting the request bit high again. - # Some brands do not respect our workaround without multiple messages on the bus, for example - if above_limit_frames > max_above_limit_frames: - request = False - - if above_limit_frames >= max_above_limit_frames + max_mismatching_frames: - above_limit_frames = 0 - - return above_limit_frames, request - - -def apply_center_deadzone(error, deadzone): - if (error > - deadzone) and (error < deadzone): - error = 0. - return error - - -def rate_limit(new_value, last_value, dw_step, up_step): - return clip(new_value, last_value + dw_step, last_value + up_step) - - -def get_friction(lateral_accel_error: float, lateral_accel_deadzone: float, friction_threshold: float, - torque_params: car.CarParams.LateralTorqueTuning, friction_compensation: bool) -> float: - friction_interp = interp( - apply_center_deadzone(lateral_accel_error, lateral_accel_deadzone), - [-friction_threshold, friction_threshold], - [-torque_params.friction, torque_params.friction] - ) - friction = float(friction_interp) if friction_compensation else 0.0 - return friction - - -def make_tester_present_msg(addr, bus, subaddr=None, suppress_response=False): - dat = [0x02, SERVICE_TYPE.TESTER_PRESENT] - if subaddr is not None: - dat.insert(0, subaddr) - dat.append(0x80 if suppress_response else 0x0) # sub-function - - dat.extend([0x0] * (8 - len(dat))) - return CanData(addr, bytes(dat), bus) - - -def get_safety_config(safety_model, safety_param = None): - ret = car.CarParams.SafetyConfig.new_message() - ret.safetyModel = safety_model - if safety_param is not None: - ret.safetyParam = safety_param - return ret - - -class CanBusBase: - offset: int - - def __init__(self, CP, fingerprint: dict[int, dict[int, int]] | None) -> None: - if CP is None: - assert fingerprint is not None - num = max([k for k, v in fingerprint.items() if len(v)], default=0) // 4 + 1 - else: - num = len(CP.safetyConfigs) - self.offset = 4 * (num - 1) - - -class CanSignalRateCalculator: - """ - Calculates the instantaneous rate of a CAN signal by using the counter - variable and the known frequency of the CAN message that contains it. - """ - def __init__(self, frequency): - self.frequency = frequency - self.previous_counter = 0 - self.previous_value = 0 - self.rate = 0 - - def update(self, current_value, current_counter): - if current_counter != self.previous_counter: - self.rate = (current_value - self.previous_value) * self.frequency - - self.previous_counter = current_counter - self.previous_value = current_value - - return self.rate - - -@dataclass(frozen=True, kw_only=True) -class CarSpecs: - mass: float # kg, curb weight - wheelbase: float # meters - steerRatio: float - centerToFrontRatio: float = 0.5 - minSteerSpeed: float = 0.0 # m/s - minEnableSpeed: float = -1.0 # m/s - tireStiffnessFactor: float = 1.0 - - def override(self, **kwargs): - return replace(self, **kwargs) - - -class Freezable: - _frozen: bool = False - - def freeze(self): - if not self._frozen: - self._frozen = True - - def __setattr__(self, *args, **kwargs): - if self._frozen: - raise Exception("cannot modify frozen object") - super().__setattr__(*args, **kwargs) - - -@dataclass(order=True) -class PlatformConfig(Freezable): - car_docs: list[CarDocs] - specs: CarSpecs - - dbc_dict: DbcDict - - flags: int = 0 - - platform_str: str | None = None - - def __hash__(self) -> int: - return hash(self.platform_str) - - def override(self, **kwargs): - return replace(self, **kwargs) - - def init(self): - pass - - def __post_init__(self): - self.init() - - -class PlatformsType(EnumType): - def __new__(metacls, cls, bases, classdict, *, boundary=None, _simple=False, **kwds): - for key in classdict._member_names.keys(): - cfg: PlatformConfig = classdict[key] - cfg.platform_str = key - cfg.freeze() - return super().__new__(metacls, cls, bases, classdict, boundary=boundary, _simple=_simple, **kwds) - - -class Platforms(str, ReprEnum, metaclass=PlatformsType): - config: PlatformConfig - - def __new__(cls, platform_config: PlatformConfig): - member = str.__new__(cls, platform_config.platform_str) - member.config = platform_config - member._value_ = platform_config.platform_str - return member - - def __repr__(self): - return f"<{self.__class__.__name__}.{self.name}>" - - @classmethod - def create_dbc_map(cls) -> dict[str, DbcDict]: - return {p: p.config.dbc_dict for p in cls} - - @classmethod - def with_flags(cls, flags: IntFlag) -> set['Platforms']: - return {p for p in cls if p.config.flags & flags} diff --git a/selfdrive/car/body/__init__.py b/selfdrive/car/body/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/body/bodycan.py b/selfdrive/car/body/bodycan.py deleted file mode 100644 index 580e5025ade783..00000000000000 --- a/selfdrive/car/body/bodycan.py +++ /dev/null @@ -1,7 +0,0 @@ -def create_control(packer, torque_l, torque_r): - values = { - "TORQUE_L": torque_l, - "TORQUE_R": torque_r, - } - - return packer.make_can_msg("TORQUE_CMD", 0, values) diff --git a/selfdrive/car/body/carcontroller.py b/selfdrive/car/body/carcontroller.py deleted file mode 100644 index eebf6798a2d74c..00000000000000 --- a/selfdrive/car/body/carcontroller.py +++ /dev/null @@ -1,84 +0,0 @@ -import numpy as np - -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import DT_CTRL -from openpilot.selfdrive.car.body import bodycan -from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.pid import PIDController - - -MAX_TORQUE = 500 -MAX_TORQUE_RATE = 50 -MAX_ANGLE_ERROR = np.radians(7) -MAX_POS_INTEGRATOR = 0.2 # meters -MAX_TURN_INTEGRATOR = 0.1 # meters - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.packer = CANPacker(dbc_name) - - # PIDs - self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) - self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) - - self.torque_r_filtered = 0. - self.torque_l_filtered = 0. - - @staticmethod - def deadband_filter(torque, deadband): - if torque > 0: - torque += deadband - else: - torque -= deadband - return torque - - def update(self, CC, CS, now_nanos): - - torque_l = 0 - torque_r = 0 - - llk_valid = len(CC.orientationNED) > 1 and len(CC.angularVelocity) > 1 - if CC.enabled and llk_valid: - # Read these from the joystick - # TODO: this isn't acceleration, okay? - speed_desired = CC.actuators.accel / 5. - speed_diff_desired = -CC.actuators.steer / 2. - - speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. - speed_error = speed_desired - speed_measured - - torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) - - speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) - turn_error = speed_diff_measured - speed_diff_desired - freeze_integrator = ((turn_error < 0 and self.turn_pid.error_integral <= -MAX_TURN_INTEGRATOR) or - (turn_error > 0 and self.turn_pid.error_integral >= MAX_TURN_INTEGRATOR)) - torque_diff = self.turn_pid.update(turn_error, freeze_integrator=freeze_integrator) - - # Combine 2 PIDs outputs - torque_r = torque + torque_diff - torque_l = torque - torque_diff - - # Torque rate limits - self.torque_r_filtered = np.clip(self.deadband_filter(torque_r, 10), - self.torque_r_filtered - MAX_TORQUE_RATE, - self.torque_r_filtered + MAX_TORQUE_RATE) - self.torque_l_filtered = np.clip(self.deadband_filter(torque_l, 10), - self.torque_l_filtered - MAX_TORQUE_RATE, - self.torque_l_filtered + MAX_TORQUE_RATE) - torque_r = int(np.clip(self.torque_r_filtered, -MAX_TORQUE, MAX_TORQUE)) - torque_l = int(np.clip(self.torque_l_filtered, -MAX_TORQUE, MAX_TORQUE)) - - can_sends = [] - can_sends.append(bodycan.create_control(self.packer, torque_l, torque_r)) - - new_actuators = CC.actuators.as_builder() - new_actuators.accel = torque_l - new_actuators.steer = torque_r - new_actuators.steerOutputCan = torque_r - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/body/carstate.py b/selfdrive/car/body/carstate.py deleted file mode 100644 index fca9bcc627432e..00000000000000 --- a/selfdrive/car/body/carstate.py +++ /dev/null @@ -1,40 +0,0 @@ -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.body.values import DBC - -STARTUP_TICKS = 100 - -class CarState(CarStateBase): - def update(self, cp): - ret = car.CarState.new_message() - - ret.wheelSpeeds.fl = cp.vl['MOTORS_DATA']['SPEED_L'] - ret.wheelSpeeds.fr = cp.vl['MOTORS_DATA']['SPEED_R'] - - ret.vEgoRaw = ((ret.wheelSpeeds.fl + ret.wheelSpeeds.fr) / 2.) * self.CP.wheelSpeedFactor - - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = False - - ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], - cp.vl['VAR_VALUES']['FAULT']]) - - ret.charging = cp.vl["BODY_DATA"]["CHARGER_CONNECTED"] == 1 - ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 - - # irrelevant for non-car - ret.gearShifter = car.CarState.GearShifter.drive - ret.cruiseState.enabled = True - ret.cruiseState.available = True - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - ("MOTORS_DATA", 100), - ("VAR_VALUES", 10), - ("BODY_DATA", 1), - ] - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) diff --git a/selfdrive/car/body/fingerprints.py b/selfdrive/car/body/fingerprints.py deleted file mode 100644 index ab7a5f8d7b3408..00000000000000 --- a/selfdrive/car/body/fingerprints.py +++ /dev/null @@ -1,28 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.body.values import CAR - -Ecu = car.CarParams.Ecu - -# debug ecu fw version is the git hash of the firmware - - -FINGERPRINTS = { - CAR.COMMA_BODY: [{ - 513: 8, 516: 8, 514: 3, 515: 4 - }], -} - -FW_VERSIONS = { - CAR.COMMA_BODY: { - (Ecu.engine, 0x720, None): [ - b'0.0.01', - b'0.3.00a', - b'02/27/2022', - ], - (Ecu.debug, 0x721, None): [ - b'166bd860', - b'dc780f85', - ], - }, -} diff --git a/selfdrive/car/body/interface.py b/selfdrive/car/body/interface.py deleted file mode 100644 index 50564d3ed806f2..00000000000000 --- a/selfdrive/car/body/interface.py +++ /dev/null @@ -1,38 +0,0 @@ -import math -from cereal import car -from openpilot.selfdrive.car import DT_CTRL, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.notCar = True - ret.carName = "body" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.body)] - - ret.minSteerSpeed = -math.inf - ret.maxLateralAccel = math.inf # TODO: set to a reasonable value - ret.steerLimitTimer = 1.0 - ret.steerActuatorDelay = 0. - - ret.wheelSpeedFactor = SPEED_FROM_RPM - - ret.radarUnavailable = True - ret.openpilotLongitudinalControl = True - ret.steerControlType = car.CarParams.SteerControlType.angle - - return ret - - def _update(self, c): - ret = self.CS.update(self.cp) - - # wait for everything to init first - if self.frame > int(5. / DT_CTRL): - # body always wants to enable - ret.init('events', 1) - ret.events[0].name = car.CarEvent.EventName.pcmEnable - ret.events[0].enable = True - self.frame += 1 - - return ret diff --git a/selfdrive/car/body/radar_interface.py b/selfdrive/car/body/radar_interface.py deleted file mode 100644 index e654bd61fd4afd..00000000000000 --- a/selfdrive/car/body/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py deleted file mode 100644 index a1195f7cb539c3..00000000000000 --- a/selfdrive/car/body/values.py +++ /dev/null @@ -1,40 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - -SPEED_FROM_RPM = 0.008587 - - -class CarControllerParams: - ANGLE_DELTA_BP = [0., 5., 15.] - ANGLE_DELTA_V = [5., .8, .15] # windup limit - ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit - LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower - STEER_THRESHOLD = 1.0 - - def __init__(self, CP): - pass - - -class CAR(Platforms): - COMMA_BODY = PlatformConfig( - [CarDocs("comma body", package="All")], - CarSpecs(mass=9, wheelbase=0.406, steerRatio=0.5, centerToFrontRatio=0.44), - dbc_dict('comma_body', None), - ) - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - bus=0, - ), - ], -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/can_definitions.py b/selfdrive/car/can_definitions.py deleted file mode 100644 index 2dba7f26a862af..00000000000000 --- a/selfdrive/car/can_definitions.py +++ /dev/null @@ -1,15 +0,0 @@ -from collections.abc import Callable -from typing import NamedTuple, Protocol - - -class CanData(NamedTuple): - address: int - dat: bytes - src: int - - -CanSendCallable = Callable[[list[CanData]], None] - - -class CanRecvCallable(Protocol): - def __call__(self, wait_for_one: bool = False) -> list[list[CanData]]: ... diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py deleted file mode 100644 index 823f038a9c22cd..00000000000000 --- a/selfdrive/car/car_helpers.py +++ /dev/null @@ -1,178 +0,0 @@ -import os -import time - -from cereal import car -from openpilot.selfdrive.car import carlog, gen_empty_fingerprint -from openpilot.selfdrive.car.can_definitions import CanRecvCallable, CanSendCallable -from openpilot.selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars -from openpilot.selfdrive.car.fw_versions import ObdCallback, get_fw_versions_ordered, get_present_ecus, match_fw_to_car -from openpilot.selfdrive.car.interfaces import get_interface_attr -from openpilot.selfdrive.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.vin import get_vin, is_valid_vin, VIN_UNKNOWN - -FRAME_FINGERPRINT = 100 # 1s - - -def load_interfaces(brand_names): - ret = {} - for brand_name in brand_names: - path = f'openpilot.selfdrive.car.{brand_name}' - CarInterface = __import__(path + '.interface', fromlist=['CarInterface']).CarInterface - CarState = __import__(path + '.carstate', fromlist=['CarState']).CarState - CarController = __import__(path + '.carcontroller', fromlist=['CarController']).CarController - for model_name in brand_names[brand_name]: - ret[model_name] = (CarInterface, CarController, CarState) - return ret - - -def _get_interface_names() -> dict[str, list[str]]: - # returns a dict of brand name and its respective models - brand_names = {} - for brand_name, brand_models in get_interface_attr("CAR").items(): - brand_names[brand_name] = [model.value for model in brand_models] - - return brand_names - - -# imports from directory selfdrive/car// -interface_names = _get_interface_names() -interfaces = load_interfaces(interface_names) - - -def can_fingerprint(can_recv: CanRecvCallable) -> tuple[str | None, dict[int, dict]]: - finger = gen_empty_fingerprint() - candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 - frame = 0 - car_fingerprint = None - done = False - - while not done: - # can_recv(wait_for_one=True) may return zero or multiple packets, so we increment frame for each one we receive - can_packets = can_recv(wait_for_one=True) - for can_packet in can_packets: - for can in can_packet: - # The fingerprint dict is generated for all buses, this way the car interface - # can use it to detect a (valid) multipanda setup and initialize accordingly - if can.src < 128: - if can.src not in finger: - finger[can.src] = {} - finger[can.src][can.address] = len(can.dat) - - for b in candidate_cars: - # Ignore extended messages and VIN query response. - if can.src == b and can.address < 0x800 and can.address not in (0x7df, 0x7e0, 0x7e8): - candidate_cars[b] = eliminate_incompatible_cars(can, candidate_cars[b]) - - # if we only have one car choice and the time since we got our first - # message has elapsed, exit - for b in candidate_cars: - if len(candidate_cars[b]) == 1 and frame > FRAME_FINGERPRINT: - # fingerprint done - car_fingerprint = candidate_cars[b][0] - - # bail if no cars left or we've been waiting for more than 2s - failed = (all(len(cc) == 0 for cc in candidate_cars.values()) and frame > FRAME_FINGERPRINT) or frame > 200 - succeeded = car_fingerprint is not None - done = failed or succeeded - - frame += 1 - - return car_fingerprint, finger - - -# **** for use live only **** -def fingerprint(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, num_pandas: int, - cached_params: type[car.CarParams] | None) -> tuple[str | None, dict, str, list, int, bool]: - fixed_fingerprint = os.environ.get('FINGERPRINT', "") - skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) - disable_fw_cache = os.environ.get('DISABLE_FW_CACHE', False) - ecu_rx_addrs = set() - - start_time = time.monotonic() - if not skip_fw_query: - if cached_params is not None and cached_params.carName != "mock" and len(cached_params.carFw) > 0 and \ - cached_params.carVin is not VIN_UNKNOWN and not disable_fw_cache: - carlog.warning("Using cached CarParams") - vin_rx_addr, vin_rx_bus, vin = -1, -1, cached_params.carVin - car_fw = list(cached_params.carFw) - cached = True - else: - carlog.warning("Getting VIN & FW versions") - # enable OBD multiplexing for VIN query - # NOTE: this takes ~0.1s and is relied on to allow sendcan subscriber to connect in time - set_obd_multiplexing(True) - # VIN query only reliably works through OBDII - vin_rx_addr, vin_rx_bus, vin = get_vin(can_recv, can_send, (0, 1)) - ecu_rx_addrs = get_present_ecus(can_recv, can_send, set_obd_multiplexing, num_pandas=num_pandas) - car_fw = get_fw_versions_ordered(can_recv, can_send, set_obd_multiplexing, vin, ecu_rx_addrs, num_pandas=num_pandas) - cached = False - - exact_fw_match, fw_candidates = match_fw_to_car(car_fw, vin) - else: - vin_rx_addr, vin_rx_bus, vin = -1, -1, VIN_UNKNOWN - exact_fw_match, fw_candidates, car_fw = True, set(), [] - cached = False - - if not is_valid_vin(vin): - carlog.error({"event": "Malformed VIN", "vin": vin}) - vin = VIN_UNKNOWN - carlog.warning("VIN %s", vin) - - # disable OBD multiplexing for CAN fingerprinting and potential ECU knockouts - set_obd_multiplexing(False) - - fw_query_time = time.monotonic() - start_time - - # CAN fingerprint - # drain CAN socket so we get the latest messages - can_recv() - car_fingerprint, finger = can_fingerprint(can_recv) - - exact_match = True - source = car.CarParams.FingerprintSource.can - - # If FW query returns exactly 1 candidate, use it - if len(fw_candidates) == 1: - car_fingerprint = list(fw_candidates)[0] - source = car.CarParams.FingerprintSource.fw - exact_match = exact_fw_match - - if fixed_fingerprint: - car_fingerprint = fixed_fingerprint - source = car.CarParams.FingerprintSource.fixed - - carlog.error({"event": "fingerprinted", "car_fingerprint": str(car_fingerprint), "source": source, "fuzzy": not exact_match, - "cached": cached, "fw_count": len(car_fw), "ecu_responses": list(ecu_rx_addrs), "vin_rx_addr": vin_rx_addr, - "vin_rx_bus": vin_rx_bus, "fingerprints": repr(finger), "fw_query_time": fw_query_time}) - - return car_fingerprint, finger, vin, car_fw, source, exact_match - - -def get_car_interface(CP): - CarInterface, CarController, CarState = interfaces[CP.carFingerprint] - return CarInterface(CP, CarController, CarState) - - -def get_car(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, experimental_long_allowed: bool, - num_pandas: int = 1, cached_params: type[car.CarParams] | None = None): - candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(can_recv, can_send, set_obd_multiplexing, num_pandas, cached_params) - - if candidate is None: - carlog.error({"event": "car doesn't match any fingerprints", "fingerprints": repr(fingerprints)}) - candidate = "MOCK" - - CarInterface, _, _ = interfaces[candidate] - CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) - CP.carVin = vin - CP.carFw = car_fw - CP.fingerprintSource = source - CP.fuzzyFingerprint = not exact_match - - return get_car_interface(CP) - - -def get_demo_car_params(): - platform = MOCK.MOCK - CarInterface, _, _ = interfaces[platform] - CP = CarInterface.get_non_essential_params(platform) - return CP diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py new file mode 100644 index 00000000000000..899f56beb0f5df --- /dev/null +++ b/selfdrive/car/car_specific.py @@ -0,0 +1,254 @@ +from cereal import car +import cereal.messaging as messaging +from opendbc.car import DT_CTRL, structs +from opendbc.car.interfaces import MAX_CTRL_SPEED, CarStateBase, CarControllerBase +from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams +from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS + +from openpilot.selfdrive.controls.lib.events import Events + +ButtonType = structs.CarState.ButtonEvent.Type +GearShifter = structs.CarState.GearShifter +EventName = car.CarEvent.EventName +NetworkLocation = structs.CarParams.NetworkLocation + + +# TODO: the goal is to abstract this file into the CarState struct and make events generic +class MockCarState: + def __init__(self): + self.sm = messaging.SubMaster(['gpsLocation', 'gpsLocationExternal']) + + def update(self, CS: car.CarState): + self.sm.update(0) + gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' + + CS.vEgo = self.sm[gps_sock].speed + CS.vEgoRaw = self.sm[gps_sock].speed + + return CS + + +class CarSpecificEvents: + def __init__(self, CP: structs.CarParams): + self.CP = CP + + self.steering_unpressed = 0 + self.low_speed_alert = False + self.no_steer_warning = False + self.silent_steer_warning = True + + def update(self, CS: CarStateBase, CS_prev: car.CarState, CC: CarControllerBase, CC_prev: car.CarControl): + if self.CP.carName in ('body', 'mock'): + events = Events() + + elif self.CP.carName == 'subaru': + events = self.create_common_events(CS.out, CS_prev) + + elif self.CP.carName == 'ford': + events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.manumatic]) + + elif self.CP.carName == 'nissan': + events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.brake]) + + if CS.lkas_enabled: # type: ignore[attr-defined] + events.add(EventName.invalidLkasSetting) + + elif self.CP.carName == 'mazda': + events = self.create_common_events(CS.out, CS_prev) + + if CS.lkas_disabled: # type: ignore[attr-defined] + events.add(EventName.lkasDisabled) + elif CS.low_speed_alert: # type: ignore[attr-defined] + events.add(EventName.belowSteerSpeed) + + elif self.CP.carName == 'chrysler': + events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.low]) + + # Low speed steer alert hysteresis logic + if self.CP.minSteerSpeed > 0. and CS.out.vEgo < (self.CP.minSteerSpeed + 0.5): + self.low_speed_alert = True + elif CS.out.vEgo > (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + elif self.CP.carName == 'honda': + events = self.create_common_events(CS.out, CS_prev, pcm_enable=False) + + if self.CP.pcmCruise and CS.out.vEgo < self.CP.minEnableSpeed: + events.add(EventName.belowEngageSpeed) + + if self.CP.pcmCruise: + # we engage when pcm is active (rising edge) + if CS.out.cruiseState.enabled and not CS_prev.cruiseState.enabled: + events.add(EventName.pcmEnable) + elif not CS.out.cruiseState.enabled and (CC_prev.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): + # it can happen that car cruise disables while comma system is enabled: need to + # keep braking if needed or if the speed is very low + if CS.out.vEgo < self.CP.minEnableSpeed + 2.: + # non loud alert if cruise disables below 25mph as expected (+ a little margin) + events.add(EventName.speedTooLow) + else: + events.add(EventName.cruiseDisabled) + if self.CP.minEnableSpeed > 0 and CS.out.vEgo < 0.001: + events.add(EventName.manualRestart) + + elif self.CP.carName == 'toyota': + events = self.create_common_events(CS.out, CS_prev) + + if self.CP.openpilotLongitudinalControl: + if CS.out.cruiseState.standstill and not CS.out.brakePressed: + events.add(EventName.resumeRequired) + if CS.low_speed_lockout: # type: ignore[attr-defined] + events.add(EventName.lowSpeedLockout) + if CS.out.vEgo < self.CP.minEnableSpeed: + events.add(EventName.belowEngageSpeed) + if CC_prev.actuators.accel > 0.3: + # some margin on the actuator to not false trigger cancellation while stopping + events.add(EventName.speedTooLow) + if CS.out.vEgo < 0.001: + # while in standstill, send a user alert + events.add(EventName.manualRestart) + + elif self.CP.carName == 'gm': + # The ECM allows enabling on falling edge of set, but only rising edge of resume + events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.sport, GearShifter.low, + GearShifter.eco, GearShifter.manumatic], + pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) + if not self.CP.pcmCruise: + if any(b.type == ButtonType.accelCruise and b.pressed for b in CS.out.buttonEvents): + events.add(EventName.buttonEnable) + + # Enabling at a standstill with brake is allowed + # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs + below_min_enable_speed = CS.out.vEgo < self.CP.minEnableSpeed or CS.moving_backward # type: ignore[attr-defined] + if below_min_enable_speed and not (CS.out.standstill and CS.out.brake >= 20 and + self.CP.networkLocation == NetworkLocation.fwdCamera): + events.add(EventName.belowEngageSpeed) + if CS.out.cruiseState.standstill: + events.add(EventName.resumeRequired) + if CS.out.vEgo < self.CP.minSteerSpeed: + events.add(EventName.belowSteerSpeed) + + elif self.CP.carName == 'volkswagen': + events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], + pcm_enable=not self.CP.openpilotLongitudinalControl, + enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) + + # Low speed steer alert hysteresis logic + if (self.CP.minSteerSpeed - 1e-3) > VWCarControllerParams.DEFAULT_MIN_STEER_SPEED and CS.out.vEgo < (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = True + elif CS.out.vEgo > (self.CP.minSteerSpeed + 2.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + if self.CP.openpilotLongitudinalControl: + if CS.out.vEgo < self.CP.minEnableSpeed + 0.5: + events.add(EventName.belowEngageSpeed) + if CC_prev.enabled and CS.out.vEgo < self.CP.minEnableSpeed: + events.add(EventName.speedTooLow) + + if CC.eps_timer_soft_disable_alert: # type: ignore[attr-defined] + events.add(EventName.steerTimeLimit) + + elif self.CP.carName == 'hyundai': + # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state + # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons + # Main button also can trigger an engagement on these cars + allow_enable = any(btn in HYUNDAI_ENABLE_BUTTONS for btn in CS.cruise_buttons) or any(CS.main_buttons) # type: ignore[attr-defined] + events = self.create_common_events(CS.out, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=allow_enable) + + # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) + if CS.out.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: + self.low_speed_alert = True + if CS.out.vEgo > (self.CP.minSteerSpeed + 4.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + else: + raise ValueError(f"Unsupported car: {self.CP.carName}") + + return events + + def create_common_events(self, CS: structs.CarState, CS_prev: car.CarState, extra_gears=None, pcm_enable=True, + allow_enable=True, enable_buttons=(ButtonType.accelCruise, ButtonType.decelCruise)): + events = Events() + + if CS.doorOpen: + events.add(EventName.doorOpen) + if CS.seatbeltUnlatched: + events.add(EventName.seatbeltNotLatched) + if CS.gearShifter != GearShifter.drive and (extra_gears is None or + CS.gearShifter not in extra_gears): + events.add(EventName.wrongGear) + if CS.gearShifter == GearShifter.reverse: + events.add(EventName.reverseGear) + if not CS.cruiseState.available: + events.add(EventName.wrongCarMode) + if CS.espDisabled: + events.add(EventName.espDisabled) + if CS.espActive: + events.add(EventName.espActive) + if CS.stockFcw: + events.add(EventName.stockFcw) + if CS.stockAeb: + events.add(EventName.stockAeb) + if CS.vEgo > MAX_CTRL_SPEED: + events.add(EventName.speedTooHigh) + if CS.cruiseState.nonAdaptive: + events.add(EventName.wrongCruiseMode) + if CS.brakeHoldActive and self.CP.openpilotLongitudinalControl: + events.add(EventName.brakeHold) + if CS.parkingBrake: + events.add(EventName.parkBrake) + if CS.accFaulted: + events.add(EventName.accFaulted) + if CS.steeringPressed: + events.add(EventName.steerOverride) + if CS.brakePressed and CS.standstill: + events.add(EventName.preEnableStandstill) + if CS.gasPressed: + events.add(EventName.gasPressedOverride) + if CS.vehicleSensorsInvalid: + events.add(EventName.vehicleSensorsInvalid) + + # Handle button presses + for b in CS.buttonEvents: + # Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port) + if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed): + events.add(EventName.buttonEnable) + # Disable on rising and falling edge of cancel for both stock and OP long + if b.type == ButtonType.cancel: + events.add(EventName.buttonCancel) + + # Handle permanent and temporary steering faults + self.steering_unpressed = 0 if CS.steeringPressed else self.steering_unpressed + 1 + if CS.steerFaultTemporary: + if CS.steeringPressed and (not CS_prev.steerFaultTemporary or self.no_steer_warning): + self.no_steer_warning = True + else: + self.no_steer_warning = False + + # if the user overrode recently, show a less harsh alert + if self.silent_steer_warning or CS.standstill or self.steering_unpressed < int(1.5 / DT_CTRL): + self.silent_steer_warning = True + events.add(EventName.steerTempUnavailableSilent) + else: + events.add(EventName.steerTempUnavailable) + else: + self.no_steer_warning = False + self.silent_steer_warning = False + if CS.steerFaultPermanent: + events.add(EventName.steerUnavailable) + + # we engage when pcm is active (rising edge) + # enabling can optionally be blocked by the car interface + if pcm_enable: + if CS.cruiseState.enabled and not CS_prev.cruiseState.enabled and allow_enable: + events.add(EventName.pcmEnable) + elif not CS.cruiseState.enabled: + events.add(EventName.pcmDisable) + + return events diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index d091f310427fd9..47bef0349e6874 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -1,6 +1,8 @@ #!/usr/bin/env python3 +import capnp import os import time +from typing import Any import cereal.messaging as messaging @@ -12,15 +14,17 @@ from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper from openpilot.common.swaglog import cloudlog, ForwardingHandler +from opendbc.car import DT_CTRL, carlog, structs +from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable +from opendbc.car.fw_versions import ObdCallback +from opendbc.car.car_helpers import get_car +from opendbc.car.interfaces import CarInterfaceBase from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp -from openpilot.selfdrive.car import DT_CTRL, carlog -from openpilot.selfdrive.car.can_definitions import CanData, CanRecvCallable, CanSendCallable -from openpilot.selfdrive.car.fw_versions import ObdCallback -from openpilot.selfdrive.car.car_helpers import get_car -from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.car_specific import CarSpecificEvents, MockCarState from openpilot.selfdrive.controls.lib.events import Events REPLAY = "REPLAY" in os.environ +_FIELDS = '__dataclass_fields__' # copy of dataclasses._FIELDS EventName = car.CarEvent.EventName @@ -57,8 +61,74 @@ def can_send(msgs: list[CanData]) -> None: return can_recv, can_send +def is_dataclass(obj): + """Similar to dataclasses.is_dataclass without instance type check checking""" + return hasattr(obj, _FIELDS) + + +def asdictref(obj) -> dict[str, Any]: + """ + Similar to dataclasses.asdict without recursive type checking and copy.deepcopy + Note that the resulting dict will contain references to the original struct as a result + """ + if not is_dataclass(obj): + raise TypeError("asdictref() should be called on dataclass instances") + + def _asdictref_inner(obj) -> dict[str, Any] | Any: + if is_dataclass(obj): + ret = {} + for field in getattr(obj, _FIELDS): # similar to dataclasses.fields() + ret[field] = _asdictref_inner(getattr(obj, field)) + return ret + elif isinstance(obj, (tuple, list)): + return type(obj)(_asdictref_inner(v) for v in obj) + else: + return obj + + return _asdictref_inner(obj) + + +def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarControl.Actuators) -> capnp.lib.capnp._DynamicStructBuilder: + struct_dict = asdictref(struct) + + if isinstance(struct, structs.CarParams): + del struct_dict['lateralTuning'] + struct_capnp = car.CarParams.new_message(**struct_dict) + + # this is the only union, special handling + which = struct.lateralTuning.which() + struct_capnp.lateralTuning.init(which) + lateralTuning_dict = asdictref(getattr(struct.lateralTuning, which)) + setattr(struct_capnp.lateralTuning, which, lateralTuning_dict) + elif isinstance(struct, structs.CarState): + struct_capnp = car.CarState.new_message(**struct_dict) + elif isinstance(struct, structs.CarControl.Actuators): + struct_capnp = car.CarControl.Actuators.new_message(**struct_dict) + else: + raise ValueError(f"Unsupported struct type: {type(struct)}") + + return struct_capnp + + +def convert_carControl(struct: capnp.lib.capnp._DynamicStructReader) -> structs.CarControl: + # TODO: recursively handle any car struct as needed + def remove_deprecated(s: dict) -> dict: + return {k: v for k, v in s.items() if not k.endswith('DEPRECATED')} + + struct_dict = struct.to_dict() + struct_dataclass = structs.CarControl(**remove_deprecated({k: v for k, v in struct_dict.items() if not isinstance(k, dict)})) + + struct_dataclass.actuators = structs.CarControl.Actuators(**remove_deprecated(struct_dict.get('actuators', {}))) + struct_dataclass.cruiseControl = structs.CarControl.CruiseControl(**remove_deprecated(struct_dict.get('cruiseControl', {}))) + struct_dataclass.hudControl = structs.CarControl.HUDControl(**remove_deprecated(struct_dict.get('hudControl', {}))) + + return struct_dataclass + + class Car: CI: CarInterfaceBase + CP: structs.CarParams + CP_capnp: car.CarParams def __init__(self, CI=None) -> None: self.can_sock = messaging.sub_sock('can', timeout=20) @@ -71,7 +141,7 @@ def __init__(self, CI=None) -> None: self.CS_prev = car.CarState.new_message() self.initialized_prev = False - self.last_actuators_output = car.CarControl.Actuators.new_message() + self.last_actuators_output = structs.CarControl.Actuators() self.params = Params() @@ -92,7 +162,7 @@ def __init__(self, CI=None) -> None: cached_params_raw = self.params.get("CarParamsCache") if cached_params_raw is not None: with car.CarParams.from_bytes(cached_params_raw) as _cached_params: - cached_params = _cached_params + cached_params = structs.CarParams(carName=_cached_params.carName, carFw=_cached_params.carFw, carVin=_cached_params.carVin) self.CI = get_car(*self.can_callbacks, obd_callback(self.params), experimental_long_allowed, num_pandas, cached_params) self.CP = self.CI.CP @@ -114,8 +184,8 @@ def __init__(self, CI=None) -> None: self.CP.passive = not controller_available or self.CP.dashcamOnly if self.CP.passive: - safety_config = car.CarParams.SafetyConfig.new_message() - safety_config.safetyModel = car.CarParams.SafetyModel.noOutput + safety_config = structs.CarParams.SafetyConfig() + safety_config.safetyModel = structs.CarParams.SafetyModel.noOutput self.CP.safetyConfigs = [safety_config] # Write previous route's CarParams @@ -124,13 +194,18 @@ def __init__(self, CI=None) -> None: self.params.put("CarParamsPrevRoute", prev_cp) # Write CarParams for controls and radard - cp_bytes = self.CP.to_bytes() + # convert to pycapnp representation for caching and logging + self.CP_capnp = convert_to_capnp(self.CP) + cp_bytes = self.CP_capnp.to_bytes() self.params.put("CarParams", cp_bytes) self.params.put_nonblocking("CarParamsCache", cp_bytes) self.params.put_nonblocking("CarParamsPersistent", cp_bytes) self.events = Events() + self.car_events = CarSpecificEvents(self.CP) + self.mock_carstate = MockCarState() + # card is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) @@ -139,7 +214,10 @@ def state_update(self) -> car.CarState: # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) - CS = self.CI.update(self.CC_prev, can_capnp_to_list(can_strs)) + CS = convert_to_capnp(self.CI.update(can_capnp_to_list(can_strs))) + + if self.CP.carName == 'mock': + CS = self.mock_carstate.update(CS) self.sm.update(0) @@ -154,11 +232,19 @@ def state_update(self) -> car.CarState: return CS - def update_events(self, CS: car.CarState) -> car.CarState: + def update_events(self, CS: car.CarState): self.events.clear() + CS.events = self.car_events.update(self.CI.CS, self.CS_prev, self.CI.CC, self.CC_prev).to_msg() + self.events.add_from_msg(CS.events) + if self.CP.notCar: + # wait for everything to init first + if self.sm.frame > int(5. / DT_CTRL) and self.initialized_prev: + # body always wants to enable + self.events.add(EventName.pcmEnable) + # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \ @@ -174,13 +260,13 @@ def state_publish(self, CS: car.CarState): if self.sm.frame % int(50. / DT_CTRL) == 0: cp_send = messaging.new_message('carParams') cp_send.valid = True - cp_send.carParams = self.CP + cp_send.carParams = self.CP_capnp self.pm.send('carParams', cp_send) # publish new carOutput co_send = messaging.new_message('carOutput') co_send.valid = self.sm.all_checks(['carControl']) - co_send.carOutput.actuatorsOutput = self.last_actuators_output + co_send.carOutput.actuatorsOutput = convert_to_capnp(self.last_actuators_output) self.pm.send('carOutput', co_send) # kick off controlsd step while we actuate the latest carControl packet @@ -204,7 +290,7 @@ def controls_update(self, CS: car.CarState, CC: car.CarControl): if self.sm.all_alive(['carControl']): # send car controls over can now_nanos = self.can_log_mono_time if REPLAY else int(time.monotonic() * 1e9) - self.last_actuators_output, can_sends = self.CI.apply(CC, now_nanos) + self.last_actuators_output, can_sends = self.CI.apply(convert_carControl(CC), now_nanos) self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) self.CC_prev = CC diff --git a/selfdrive/car/chrysler/__init__.py b/selfdrive/car/chrysler/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py deleted file mode 100644 index c194488de967c3..00000000000000 --- a/selfdrive/car/chrysler/carcontroller.py +++ /dev/null @@ -1,83 +0,0 @@ -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import DT_CTRL, apply_meas_steer_torque_limits -from openpilot.selfdrive.car.chrysler import chryslercan -from openpilot.selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags -from openpilot.selfdrive.car.interfaces import CarControllerBase - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.apply_steer_last = 0 - - self.hud_count = 0 - self.last_lkas_falling_edge = 0 - self.lkas_control_bit_prev = False - self.last_button_frame = 0 - - self.packer = CANPacker(dbc_name) - self.params = CarControllerParams(CP) - - def update(self, CC, CS, now_nanos): - can_sends = [] - - lkas_active = CC.latActive and self.lkas_control_bit_prev - - # cruise buttons - if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: - das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 - - # ACC cancellation - if CC.cruiseControl.cancel: - self.last_button_frame = self.frame - can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) - - # ACC resume from standstill - elif CC.cruiseControl.resume: - self.last_button_frame = self.frame - can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) - - # HUD alerts - if self.frame % 25 == 0: - if CS.lkas_car_model != -1: - can_sends.append(chryslercan.create_lkas_hud(self.packer, self.CP, lkas_active, CC.hudControl.visualAlert, - self.hud_count, CS.lkas_car_model, CS.auto_high_beam)) - self.hud_count += 1 - - # steering - if self.frame % self.params.STEER_STEP == 0: - - # TODO: can we make this more sane? why is it different for all the cars? - lkas_control_bit = self.lkas_control_bit_prev - if CS.out.vEgo > self.CP.minSteerSpeed: - lkas_control_bit = True - elif self.CP.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: - if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): - lkas_control_bit = False - elif self.CP.carFingerprint in RAM_CARS: - if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): - lkas_control_bit = False - - # EPS faults if LKAS re-enables too quickly - lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) - - if not lkas_control_bit and self.lkas_control_bit_prev: - self.last_lkas_falling_edge = self.frame - self.lkas_control_bit_prev = lkas_control_bit - - # steer torque - new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) - if not lkas_active or not lkas_control_bit: - apply_steer = 0 - self.apply_steer_last = apply_steer - - can_sends.append(chryslercan.create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit)) - - self.frame += 1 - - new_actuators = CC.actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - return new_actuators, can_sends diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py deleted file mode 100644 index c8b084aa622582..00000000000000 --- a/selfdrive/car/chrysler/carstate.py +++ /dev/null @@ -1,156 +0,0 @@ -from cereal import car -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD, RAM_CARS -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.auto_high_beam = 0 - self.button_counter = 0 - self.lkas_car_model = -1 - - if CP.carFingerprint in RAM_CARS: - self.shifter_values = can_define.dv["Transmission_Status"]["Gear_State"] - else: - self.shifter_values = can_define.dv["GEAR"]["PRNDL"] - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRUISE_BUTTONS"]["ACC_Distance_Dec"] - - # lock info - ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], - cp.vl["BCM_1"]["DOOR_OPEN_FR"], - cp.vl["BCM_1"]["DOOR_OPEN_RL"], - cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["ORC_1"]["SEATBELT_DRIVER_UNLATCHED"] == 1 - - # brake pedal - ret.brake = 0 - ret.brakePressed = cp.vl["ESP_1"]['Brake_Pedal_State'] == 1 # Physical brake pedal switch - - # gas pedal - ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] - ret.gasPressed = ret.gas > 1e-5 - - # car speed - if self.CP.carFingerprint in RAM_CARS: - ret.vEgoRaw = cp.vl["ESP_8"]["Vehicle_Speed"] * CV.KPH_TO_MS - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["Transmission_Status"]["Gear_State"], None)) - else: - ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = not ret.vEgoRaw > 0.001 - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["ESP_6"]["WHEEL_SPEED_FL"], - cp.vl["ESP_6"]["WHEEL_SPEED_FR"], - cp.vl["ESP_6"]["WHEEL_SPEED_RL"], - cp.vl["ESP_6"]["WHEEL_SPEED_RR"], - unit=1, - ) - - # button presses - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, - cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) - ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 - - # steering wheel - ret.steeringAngleDeg = cp.vl["STEERING"]["STEERING_ANGLE"] + cp.vl["STEERING"]["STEERING_ANGLE_HP"] - ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] - ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] - ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # cruise state - cp_cruise = cp_cam if self.CP.carFingerprint in RAM_CARS else cp - - ret.cruiseState.available = cp_cruise.vl["DAS_3"]["ACC_AVAILABLE"] == 1 - ret.cruiseState.enabled = cp_cruise.vl["DAS_3"]["ACC_ACTIVE"] == 1 - ret.cruiseState.speed = cp_cruise.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS - ret.cruiseState.nonAdaptive = cp_cruise.vl["DAS_4"]["ACC_STATE"] in (1, 2) # 1 NormalCCOn and 2 NormalCCSet - ret.cruiseState.standstill = cp_cruise.vl["DAS_3"]["ACC_STANDSTILL"] == 1 - ret.accFaulted = cp_cruise.vl["DAS_3"]["ACC_FAULTED"] != 0 - - if self.CP.carFingerprint in RAM_CARS: - # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message - self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] - ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 - else: - ret.steerFaultTemporary = cp.vl["EPS_2"]["LKAS_TEMPORARY_FAULT"] == 1 - ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4 - - # blindspot sensors - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 - ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 - - self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] - self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] - - return ret - - @staticmethod - def get_cruise_messages(): - messages = [ - ("DAS_3", 50), - ("DAS_4", 50), - ] - return messages - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("ESP_1", 50), - ("EPS_2", 100), - ("ESP_6", 50), - ("STEERING", 100), - ("ECM_5", 50), - ("CRUISE_BUTTONS", 50), - ("STEERING_LEVERS", 10), - ("ORC_1", 2), - ("BCM_1", 1), - ] - - if CP.enableBsm: - messages.append(("BSM_1", 2)) - - if CP.carFingerprint in RAM_CARS: - messages += [ - ("ESP_8", 50), - ("EPS_3", 50), - ("Transmission_Status", 50), - ] - else: - messages += [ - ("GEAR", 50), - ("SPEED_1", 100), - ] - messages += CarState.get_cruise_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - ("DAS_6", 4), - ] - - if CP.carFingerprint in RAM_CARS: - messages += CarState.get_cruise_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py deleted file mode 100644 index 96439f35d8cf2a..00000000000000 --- a/selfdrive/car/chrysler/chryslercan.py +++ /dev/null @@ -1,71 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.chrysler.values import RAM_CARS - -GearShifter = car.CarState.GearShifter -VisualAlert = car.CarControl.HUDControl.VisualAlert - -def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, auto_high_beam): - # LKAS_HUD - Controls what lane-keeping icon is displayed - - # == Color == - # 0 hidden? - # 1 white - # 2 green - # 3 ldw - - # == Lines == - # 03 white Lines - # 04 grey lines - # 09 left lane close - # 0A right lane close - # 0B left Lane very close - # 0C right Lane very close - # 0D left cross cross - # 0E right lane cross - - # == Alerts == - # 7 Normal - # 6 lane departure place hands on wheel - - color = 2 if lkas_active else 1 - lines = 3 if lkas_active else 0 - alerts = 7 if lkas_active else 0 - - if hud_count < (1 * 4): # first 3 seconds, 4Hz - alerts = 1 - - if hud_alert in (VisualAlert.ldw, VisualAlert.steerRequired): - color = 4 - lines = 0 - alerts = 6 - - values = { - "LKAS_ICON_COLOR": color, - "CAR_MODEL": car_model, - "LKAS_LANE_LINES": lines, - "LKAS_ALERTS": alerts, - } - - if CP.carFingerprint in RAM_CARS: - values['AUTO_HIGH_BEAM_ON'] = auto_high_beam - - return packer.make_can_msg("DAS_6", 0, values) - - -def create_lkas_command(packer, CP, apply_steer, lkas_control_bit): - # LKAS_COMMAND Lane-keeping signal to turn the wheel - enabled_val = 2 if CP.carFingerprint in RAM_CARS else 1 - values = { - "STEERING_TORQUE": apply_steer, - "LKAS_CONTROL_BIT": enabled_val if lkas_control_bit else 0, - } - return packer.make_can_msg("LKAS_COMMAND", 0, values) - - -def create_cruise_buttons(packer, frame, bus, cancel=False, resume=False): - values = { - "ACC_Cancel": cancel, - "ACC_Resume": resume, - "COUNTER": frame % 0x10, - } - return packer.make_can_msg("CRUISE_BUTTONS", bus, values) diff --git a/selfdrive/car/chrysler/fingerprints.py b/selfdrive/car/chrysler/fingerprints.py deleted file mode 100644 index 1f453d8f50d4ea..00000000000000 --- a/selfdrive/car/chrysler/fingerprints.py +++ /dev/null @@ -1,716 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.chrysler.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.CHRYSLER_PACIFICA_2018: { - (Ecu.combinationMeter, 0x742, None): [ - b'68227902AF', - b'68227902AG', - b'68227902AH', - b'68227905AG', - b'68360252AC', - ], - (Ecu.srs, 0x744, None): [ - b'68211617AF', - b'68211617AG', - b'68358974AC', - b'68405937AA', - ], - (Ecu.abs, 0x747, None): [ - b'68222747AG', - b'68330876AA', - b'68330876AB', - b'68352227AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'04672758AB', - b'68226356AF', - b'68226356AH', - b'68226356AI', - ], - (Ecu.eps, 0x75a, None): [ - b'68288891AE', - b'68378884AA', - b'68525338AA', - b'68525338AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68267018AO ', - b'68267020AJ ', - b'68303534AG ', - b'68303534AJ ', - b'68340762AD ', - b'68340764AD ', - b'68352652AE ', - b'68352654AE ', - b'68366851AH ', - b'68366853AE ', - b'68366853AG ', - b'68372861AF ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'68277370AJ', - b'68277370AM', - b'68277372AD', - b'68277372AE', - b'68277372AN', - b'68277374AA', - b'68277374AB', - b'68277374AD', - b'68277374AN', - b'68367471AC', - b'68367471AD', - b'68380571AB', - ], - }, - CAR.CHRYSLER_PACIFICA_2020: { - (Ecu.combinationMeter, 0x742, None): [ - b'68405327AC', - b'68436233AB', - b'68436233AC', - b'68436234AB', - b'68436250AE', - b'68529067AA', - b'68594993AB', - b'68594994AB', - ], - (Ecu.srs, 0x744, None): [ - b'68405565AB', - b'68405565AC', - b'68444299AC', - b'68480707AC', - b'68480708AC', - b'68526663AB', - ], - (Ecu.abs, 0x747, None): [ - b'68397394AA', - b'68433480AB', - b'68453575AF', - b'68577676AA', - b'68593395AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'04672758AB', - b'68417813AF', - b'68540436AA', - b'68540436AC', - b'68540436AD', - b'68598670AB', - b'68598670AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68416742AA', - b'68460393AA', - b'68460393AB', - b'68494461AB', - b'68494461AC', - b'68524936AA', - b'68524936AB', - b'68525338AB', - b'68594337AB', - b'68594340AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68413871AD ', - b'68413871AE ', - b'68413871AH ', - b'68413871AI ', - b'68413873AH ', - b'68413873AI ', - b'68443120AE ', - b'68443123AC ', - b'68443125AC ', - b'68496647AI ', - b'68496647AJ ', - b'68496650AH ', - b'68496650AI ', - b'68496652AH ', - b'68526752AD ', - b'68526752AE ', - b'68526754AE ', - b'68536264AE ', - b'68700304AB ', - b'68700306AB ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'68414271AC', - b'68414271AD', - b'68414275AC', - b'68414275AD', - b'68443154AB', - b'68443155AC', - b'68443158AB', - b'68501050AD', - b'68501051AD', - b'68501055AD', - b'68527221AB', - b'68527223AB', - b'68586231AD', - b'68586233AD', - ], - }, - CAR.CHRYSLER_PACIFICA_2018_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'68239262AH', - b'68239262AI', - b'68239262AJ', - b'68239263AH', - b'68239263AJ', - b'68358439AE', - b'68358439AG', - ], - (Ecu.srs, 0x744, None): [ - b'68238840AH', - b'68358990AC', - b'68405939AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'68226356AI', - ], - (Ecu.eps, 0x75a, None): [ - b'68288309AC', - b'68288309AD', - b'68525339AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'68277480AV ', - b'68277480AX ', - b'68277480AZ ', - b'68366580AI ', - b'68366580AK ', - b'68366580AM ', - ], - (Ecu.hybrid, 0x7e2, None): [ - b'05190175BF', - b'05190175BH', - b'05190226AI', - b'05190226AK', - b'05190226AM', - ], - }, - CAR.CHRYSLER_PACIFICA_2019_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'68405292AC', - b'68434956AC', - b'68434956AD', - b'68434960AE', - b'68434960AF', - b'68529064AB', - b'68594990AB', - ], - (Ecu.srs, 0x744, None): [ - b'68405567AB', - b'68405567AC', - b'68453076AD', - b'68480710AC', - b'68526665AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AB', - b'68417813AF', - b'68540436AA', - b'68540436AB', - b'68540436AC', - b'68540436AD', - b'68598670AB', - b'68598670AC', - b'68645752AA', - ], - (Ecu.eps, 0x75a, None): [ - b'68416741AA', - b'68460392AA', - b'68525339AA', - b'68525339AB', - b'68594341AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68416680AE ', - b'68416680AF ', - b'68416680AG ', - b'68444228AC ', - b'68444228AD ', - b'68444228AE ', - b'68444228AF ', - b'68499122AD ', - b'68499122AE ', - b'68499122AF ', - b'68526772AD ', - b'68526772AH ', - b'68599493AC ', - b'68657433AA ', - ], - (Ecu.hybrid, 0x7e2, None): [ - b'05185116AF', - b'05185116AJ', - b'05185116AK', - b'05190240AP', - b'05190240AQ', - b'05190240AR', - b'05190265AG', - b'05190265AH', - b'05190289AE', - b'68540977AH', - b'68540977AK', - b'68597647AE', - b'68632416AB', - ], - }, - CAR.JEEP_GRAND_CHEROKEE: { - (Ecu.combinationMeter, 0x742, None): [ - b'68243549AG', - b'68302211AC', - b'68302212AD', - b'68302223AC', - b'68302246AC', - b'68331511AC', - b'68331574AC', - b'68331687AC', - b'68331690AC', - b'68340272AD', - ], - (Ecu.srs, 0x744, None): [ - b'68309533AA', - b'68316742AB', - b'68355363AB', - ], - (Ecu.abs, 0x747, None): [ - b'68252642AG', - b'68306178AD', - b'68336275AB', - b'68336276AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672627AB', - b'68251506AF', - b'68332015AB', - ], - (Ecu.eps, 0x75a, None): [ - b'68276201AG', - b'68321644AB', - b'68321644AC', - b'68321646AC', - b'68321648AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035920AE ', - b'68252272AG ', - b'68284455AI ', - b'68284456AI ', - b'68284477AF ', - b'68325564AH ', - b'68325564AI ', - b'68325565AH ', - b'68325565AI ', - b'68325618AD ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035517AH', - b'68253222AF', - b'68311218AC', - b'68311223AF', - b'68311223AG', - b'68361911AE', - b'68361911AF', - b'68361911AH', - b'68361916AD', - ], - }, - CAR.JEEP_GRAND_CHEROKEE_2019: { - (Ecu.combinationMeter, 0x742, None): [ - b'68402703AB', - b'68402704AB', - b'68402708AB', - b'68402971AD', - b'68454144AD', - b'68454145AB', - b'68454152AB', - b'68454156AB', - b'68516650AB', - b'68516651AB', - b'68516669AB', - b'68516671AB', - b'68516683AB', - ], - (Ecu.srs, 0x744, None): [ - b'68355363AB', - b'68355364AB', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AC', - b'68408639AD', - b'68499978AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672788AA', - b'68456722AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68417279AA', - b'68417280AA', - b'68417281AA', - b'68453431AA', - b'68453433AA', - b'68453435AA', - b'68499171AA', - b'68499171AB', - b'68501183AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035674AB ', - b'68412635AG ', - b'68412660AD ', - b'68422860AB', - b'68449435AE ', - b'68496223AA ', - b'68504959AD ', - b'68504959AE ', - b'68504960AD ', - b'68504993AC ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035707AA', - b'68419672AC', - b'68419678AB', - b'68423905AB', - b'68449258AC', - b'68495807AA', - b'68495807AB', - b'68503641AC', - b'68503664AC', - ], - }, - CAR.RAM_1500_5TH_GEN: { - (Ecu.combinationMeter, 0x742, None): [ - b'68294051AG', - b'68294051AI', - b'68294052AG', - b'68294052AH', - b'68294059AI', - b'68294063AG', - b'68294063AH', - b'68294063AI', - b'68434846AC', - b'68434847AC', - b'68434849AC', - b'68434856AC', - b'68434858AC', - b'68434859AC', - b'68434860AC', - b'68453471AD', - b'68453483AC', - b'68453483AD', - b'68453487AD', - b'68453491AC', - b'68453491AD', - b'68453499AD', - b'68453503AC', - b'68453503AD', - b'68453505AC', - b'68453505AD', - b'68453511AC', - b'68453513AC', - b'68453513AD', - b'68453514AD', - b'68505633AB', - b'68510277AG', - b'68510277AH', - b'68510280AG', - b'68510282AG', - b'68510282AH', - b'68510283AG', - b'68527346AE', - b'68527361AD', - b'68527375AD', - b'68527381AD', - b'68527381AE', - b'68527382AE', - b'68527383AD', - b'68527383AE', - b'68527387AE', - b'68527397AD', - b'68527403AC', - b'68527403AD', - b'68546047AF', - b'68631938AA', - b'68631939AA', - b'68631940AA', - b'68631940AB', - b'68631942AA', - b'68631943AB', - ], - (Ecu.srs, 0x744, None): [ - b'68428609AB', - b'68441329AB', - b'68473844AB', - b'68490898AA', - b'68500728AA', - b'68615033AA', - b'68615034AA', - ], - (Ecu.abs, 0x747, None): [ - b'68292406AG', - b'68292406AH', - b'68432418AB', - b'68432418AC', - b'68432418AD', - b'68436004AD', - b'68436004AE', - b'68438454AC', - b'68438454AD', - b'68438456AE', - b'68438456AF', - b'68535469AB', - b'68535470AC', - b'68548900AB', - b'68586307AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672892AB', - b'04672932AB', - b'04672932AC', - b'22DTRHD_AA', - b'68320950AH', - b'68320950AI', - b'68320950AJ', - b'68320950AL', - b'68320950AM', - b'68454268AB', - b'68475160AE', - b'68475160AF', - b'68475160AG', - ], - (Ecu.eps, 0x75a, None): [ - b'21590101AA', - b'21590101AB', - b'68273275AF', - b'68273275AG', - b'68273275AH', - b'68312176AE', - b'68312176AF', - b'68312176AG', - b'68440789AC', - b'68466110AA', - b'68466110AB', - b'68466113AA', - b'68469901AA', - b'68469907AA', - b'68522583AA', - b'68522583AB', - b'68522584AA', - b'68522585AB', - b'68552788AA', - b'68552789AA', - b'68552790AA', - b'68552791AB', - b'68552794AA', - b'68552794AD', - b'68585106AB', - b'68585107AB', - b'68585108AB', - b'68585109AB', - b'68585112AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035699AG ', - b'05035841AC ', - b'05035841AD ', - b'05036026AB ', - b'05036065AE ', - b'05036066AE ', - b'05036067AE ', - b'05036193AA ', - b'05149368AA ', - b'05149374AA ', - b'05149591AD ', - b'05149591AE ', - b'05149592AE ', - b'05149599AE ', - b'05149600AD ', - b'05149600AE ', - b'05149605AE ', - b'05149846AA ', - b'05149848AA ', - b'05149848AC ', - b'05190341AD', - b'68378695AJ ', - b'68378696AJ ', - b'68378696AK ', - b'68378701AI ', - b'68378702AI ', - b'68378710AL ', - b'68378742AI ', - b'68378742AK ', - b'68378743AM ', - b'68378748AL ', - b'68378758AM ', - b'68448163AJ', - b'68448163AK', - b'68448163AL', - b'68448165AG', - b'68448165AK', - b'68455111AC ', - b'68455119AC ', - b'68455145AC ', - b'68455145AE ', - b'68455146AC ', - b'68460927AA ', - b'68467915AC ', - b'68467916AC ', - b'68467936AC ', - b'68500630AD', - b'68500630AE', - b'68500631AE', - b'68502719AC ', - b'68502722AC ', - b'68502733AC ', - b'68502734AF ', - b'68502740AF ', - b'68502741AF ', - b'68502742AC ', - b'68502742AF ', - b'68539650AD', - b'68539650AF', - b'68539651AD', - b'68586101AA ', - b'68586102AA ', - b'68586105AB ', - b'68629919AC ', - b'68629922AC ', - b'68629925AC ', - b'68629926AC ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035706AD', - b'05035842AB', - b'05036069AA', - b'05036181AA', - b'05149536AC', - b'05149537AC', - b'05149543AC', - b'68360078AL', - b'68360080AL', - b'68360080AM', - b'68360081AM', - b'68360085AJ', - b'68360085AL', - b'68360086AH', - b'68360086AK', - b'68360086AN', - b'68384328AD', - b'68384332AD', - b'68445531AC', - b'68445533AB', - b'68445536AB', - b'68445537AB', - b'68466081AB', - b'68466087AB', - b'68484466AC', - b'68484467AC', - b'68484471AC', - b'68502994AD', - b'68502996AD', - b'68520867AE', - b'68520867AF', - b'68520870AC', - b'68520871AC', - b'68528325AE', - b'68540431AB', - b'68540433AB', - b'68551676AA', - b'68629935AB', - b'68629936AC', - ], - }, - CAR.RAM_HD_5TH_GEN: { - (Ecu.combinationMeter, 0x742, None): [ - b'68361606AH', - b'68437735AC', - b'68492693AD', - b'68525485AB', - b'68525487AB', - b'68525498AB', - b'68528791AF', - b'68628474AB', - ], - (Ecu.srs, 0x744, None): [ - b'68399794AC', - b'68428503AA', - b'68428505AA', - b'68428507AA', - ], - (Ecu.abs, 0x747, None): [ - b'68334977AH', - b'68455481AC', - b'68504022AA', - b'68504022AB', - b'68504022AC', - b'68530686AB', - b'68530686AC', - b'68544596AC', - b'68641704AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672895AB', - b'04672934AB', - b'56029827AG', - b'56029827AH', - b'68462657AE', - b'68484694AD', - b'68484694AE', - b'68615489AB', - ], - (Ecu.eps, 0x761, None): [ - b'68421036AC', - b'68507906AB', - b'68534023AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'52370131AF', - b'52370231AF', - b'52370231AG', - b'52370491AA', - b'52370931CT', - b'52401032AE', - b'52421132AF', - b'52421332AF', - b'68527616AD ', - b'M2370131MB', - b'M2421132MB', - ], - }, - CAR.DODGE_DURANGO: { - (Ecu.combinationMeter, 0x742, None): [ - b'68454261AD', - b'68471535AE', - ], - (Ecu.srs, 0x744, None): [ - b'68355362AB', - b'68492238AD', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AD', - b'68499978AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'68440581AE', - b'68456722AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68453435AA', - b'68498477AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035786AE ', - b'68449476AE ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035826AC', - b'68449265AC', - ], - }, -} diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py deleted file mode 100755 index eb1f6703cdfa3d..00000000000000 --- a/selfdrive/car/chrysler/interface.py +++ /dev/null @@ -1,97 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.chrysler.values import CAR, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "chrysler" - ret.dashcamOnly = candidate in RAM_HD - - # radar parsing needs some work, see https://github.com/commaai/openpilot/issues/26842 - ret.radarUnavailable = True # DBC[candidate]['radar'] is None - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.4 - - # safety config - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler)] - if candidate in RAM_HD: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_HD - elif candidate in RAM_DT: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_DT - - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - if candidate not in RAM_CARS: - # Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed. - new_eps_platform = candidate in (CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.JEEP_GRAND_CHEROKEE_2019, CAR.DODGE_DURANGO) - new_eps_firmware = any(fw.ecu == 'eps' and fw.fwVersion[:4] >= b"6841" for fw in car_fw) - if new_eps_platform or new_eps_firmware: - ret.flags |= ChryslerFlags.HIGHER_MIN_STEERING_SPEED.value - - # Chrysler - if candidate in (CAR.CHRYSLER_PACIFICA_2018, CAR.CHRYSLER_PACIFICA_2018_HYBRID, CAR.CHRYSLER_PACIFICA_2019_HYBRID, - CAR.CHRYSLER_PACIFICA_2020, CAR.DODGE_DURANGO): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 - - # Jeep - elif candidate in (CAR.JEEP_GRAND_CHEROKEE, CAR.JEEP_GRAND_CHEROKEE_2019): - ret.steerActuatorDelay = 0.2 - - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 - - # Ram - elif candidate == CAR.RAM_1500_5TH_GEN: - ret.steerActuatorDelay = 0.2 - ret.wheelbase = 3.88 - # Older EPS FW allow steer to zero - if any(fw.ecu == 'eps' and b"68" < fw.fwVersion[:4] <= b"6831" for fw in car_fw): - ret.minSteerSpeed = 0. - - elif candidate == CAR.RAM_HD_5TH_GEN: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, 1.0, False) - - else: - raise ValueError(f"Unsupported car: {candidate}") - - if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: - # TODO: allow these cars to steer down to 13 m/s if already engaged. - # TODO: Durango 2020 may be able to steer to zero once above 38 kph - ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. - - ret.centerToFront = ret.wheelbase * 0.44 - ret.enableBsm = 720 in fingerprint[0] - - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) - - # Low speed steer alert hysteresis logic - if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 0.5): - self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 1.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(car.CarEvent.EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py deleted file mode 100755 index f1d863d1e15db2..00000000000000 --- a/selfdrive/car/chrysler/radar_interface.py +++ /dev/null @@ -1,85 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.can.parser import CANParser -from cereal import car -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.chrysler.values import DBC - -RADAR_MSGS_C = list(range(0x2c2, 0x2d4+2, 2)) # c_ messages 706,...,724 -RADAR_MSGS_D = list(range(0x2a2, 0x2b4+2, 2)) # d_ messages -LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) -NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) - -def _create_radar_can_parser(car_fingerprint): - dbc = DBC[car_fingerprint]['radar'] - if dbc is None: - return None - - msg_n = len(RADAR_MSGS_C) - # list of [(signal name, message name or number), (...)] - # [('RADAR_STATE', 1024), - # ('LONG_DIST', 1072), - # ('LONG_DIST', 1073), - # ('LONG_DIST', 1074), - # ('LONG_DIST', 1075), - - messages = list(zip(RADAR_MSGS_C + - RADAR_MSGS_D, - [20] * msg_n + # 20Hz (0.05s) - [20] * msg_n, strict=True)) # 20Hz (0.05s) - - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - -def _address_to_track(address): - if address in RADAR_MSGS_C: - return (address - RADAR_MSGS_C[0]) // 2 - if address in RADAR_MSGS_D: - return (address - RADAR_MSGS_D[0]) // 2 - raise ValueError("radar received unexpected address %d" % address) - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.rcp = _create_radar_can_parser(CP.carFingerprint) - self.updated_messages = set() - self.trigger_msg = LAST_MSG - - def update(self, can_strings): - if self.rcp is None or self.CP.radarUnavailable: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for ii in self.updated_messages: # ii should be the message ID as a number - cpt = self.rcp.vl[ii] - trackId = _address_to_track(ii) - - if trackId not in self.pts: - self.pts[trackId] = car.RadarData.RadarPoint.new_message() - self.pts[trackId].trackId = trackId - self.pts[trackId].aRel = float('nan') - self.pts[trackId].yvRel = float('nan') - self.pts[trackId].measured = True - - if 'LONG_DIST' in cpt: # c_* message - self.pts[trackId].dRel = cpt['LONG_DIST'] # from front of car - # our lat_dist is positive to the right in car's frame. - # TODO what does yRel want? - self.pts[trackId].yRel = cpt['LAT_DIST'] # in car frame's y axis, left is positive - else: # d_* message - self.pts[trackId].vRel = cpt['REL_SPEED'] - - # We want a list, not a dictionary. Filter out LONG_DIST==0 because that means it's not valid. - ret.points = [x for x in self.pts.values() if x.dRel != 0] - - self.updated_messages.clear() - return ret diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py deleted file mode 100644 index c44c647fd4f667..00000000000000 --- a/selfdrive/car/chrysler/values.py +++ /dev/null @@ -1,152 +0,0 @@ -from enum import IntFlag -from dataclasses import dataclass, field - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu - - -class ChryslerFlags(IntFlag): - # Detected flags - HIGHER_MIN_STEERING_SPEED = 1 - -@dataclass -class ChryslerCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC)" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.fca])) - - -@dataclass -class ChryslerPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion')) - - -@dataclass(frozen=True) -class ChryslerCarSpecs(CarSpecs): - minSteerSpeed: float = 3.8 # m/s - - -class CAR(Platforms): - # Chrysler - CHRYSLER_PACIFICA_2018_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2017-18")], - ChryslerCarSpecs(mass=2242., wheelbase=3.089, steerRatio=16.2), - ) - CHRYSLER_PACIFICA_2019_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2019-24")], - CHRYSLER_PACIFICA_2018_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2018 = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica 2017-18")], - CHRYSLER_PACIFICA_2018_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2020 = ChryslerPlatformConfig( - [ - ChryslerCarDocs("Chrysler Pacifica 2019-20"), - ChryslerCarDocs("Chrysler Pacifica 2021-23", package="All"), - ], - CHRYSLER_PACIFICA_2018_HYBRID.specs, - ) - - # Dodge - DODGE_DURANGO = ChryslerPlatformConfig( - [ChryslerCarDocs("Dodge Durango 2020-21")], - CHRYSLER_PACIFICA_2018_HYBRID.specs, - ) - - # Jeep - JEEP_GRAND_CHEROKEE = ChryslerPlatformConfig( # includes 2017 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk")], - ChryslerCarSpecs(mass=1778., wheelbase=2.71, steerRatio=16.7), - ) - - JEEP_GRAND_CHEROKEE_2019 = ChryslerPlatformConfig( # includes 2020 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4")], - JEEP_GRAND_CHEROKEE.specs, - ) - - # Ram - RAM_1500_5TH_GEN = ChryslerPlatformConfig( - [ChryslerCarDocs("Ram 1500 2019-24", car_parts=CarParts.common([CarHarness.ram]))], - ChryslerCarSpecs(mass=2493., wheelbase=3.88, steerRatio=16.3, minSteerSpeed=14.5), - dbc_dict('chrysler_ram_dt_generated', None), - ) - RAM_HD_5TH_GEN = ChryslerPlatformConfig( - [ - ChryslerCarDocs("Ram 2500 2020-24", car_parts=CarParts.common([CarHarness.ram])), - ChryslerCarDocs("Ram 3500 2019-22", car_parts=CarParts.common([CarHarness.ram])), - ], - ChryslerCarSpecs(mass=3405., wheelbase=3.785, steerRatio=15.61, minSteerSpeed=16.), - dbc_dict('chrysler_ram_hd_generated', None), - ) - - -class CarControllerParams: - def __init__(self, CP): - self.STEER_STEP = 2 # 50 Hz - self.STEER_ERROR_MAX = 80 - if CP.carFingerprint in RAM_HD: - self.STEER_DELTA_UP = 14 - self.STEER_DELTA_DOWN = 14 - self.STEER_MAX = 361 # higher than this faults the EPS - elif CP.carFingerprint in RAM_DT: - self.STEER_DELTA_UP = 6 - self.STEER_DELTA_DOWN = 6 - self.STEER_MAX = 261 # EPS allows more, up to 350? - else: - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 3 - self.STEER_MAX = 261 # higher than this faults the EPS - - -STEER_THRESHOLD = 120 - -RAM_DT = {CAR.RAM_1500_5TH_GEN, } -RAM_HD = {CAR.RAM_HD_5TH_GEN, } -RAM_CARS = RAM_DT | RAM_HD - - -CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf132) -CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf132) - -CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) -CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) - -CHRYSLER_RX_OFFSET = -0x280 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], - rx_offset=CHRYSLER_RX_OFFSET, - bus=0, - ), - Request( - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.hybrid, Ecu.engine, Ecu.transmission], - bus=0, - ), - Request( - [CHRYSLER_SOFTWARE_VERSION_REQUEST], - [CHRYSLER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - bus=0, - ), - ], - extra_ecus=[ - (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids, NOTE: not on all hybrid platforms - ], -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/conversions.py b/selfdrive/car/conversions.py deleted file mode 100644 index b02b33c625a73f..00000000000000 --- a/selfdrive/car/conversions.py +++ /dev/null @@ -1,19 +0,0 @@ -import numpy as np - -class Conversions: - # Speed - MPH_TO_KPH = 1.609344 - KPH_TO_MPH = 1. / MPH_TO_KPH - MS_TO_KPH = 3.6 - KPH_TO_MS = 1. / MS_TO_KPH - MS_TO_MPH = MS_TO_KPH * KPH_TO_MPH - MPH_TO_MS = MPH_TO_KPH * KPH_TO_MS - MS_TO_KNOTS = 1.9438 - KNOTS_TO_MS = 1. / MS_TO_KNOTS - - # Angle - DEG_TO_RAD = np.pi / 180. - RAD_TO_DEG = 1. / DEG_TO_RAD - - # Mass - LB_TO_KG = 0.453592 diff --git a/selfdrive/car/disable_ecu.py b/selfdrive/car/disable_ecu.py deleted file mode 100755 index bbf5b4c9ffc90b..00000000000000 --- a/selfdrive/car/disable_ecu.py +++ /dev/null @@ -1,49 +0,0 @@ -#!/usr/bin/env python3 -from openpilot.selfdrive.car import carlog -from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery - -EXT_DIAG_REQUEST = b'\x10\x03' -EXT_DIAG_RESPONSE = b'\x50\x03' - -COM_CONT_RESPONSE = b'' - - -def disable_ecu(can_recv, can_send, bus=0, addr=0x7d0, sub_addr=None, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False): - """Silence an ECU by disabling sending and receiving messages using UDS 0x28. - The ECU will stay silent as long as openpilot keeps sending Tester Present. - - This is used to disable the radar in some cars. Openpilot will emulate the radar. - WARNING: THIS DISABLES AEB!""" - carlog.warning(f"ecu disable {hex(addr), sub_addr} ...") - - for i in range(retry): - try: - query = IsoTpParallelQuery(can_send, can_recv, bus, [(addr, sub_addr)], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) - - for _, _ in query.get_data(timeout).items(): - carlog.warning("communication control disable tx/rx ...") - - query = IsoTpParallelQuery(can_send, can_recv, bus, [(addr, sub_addr)], [com_cont_req], [COM_CONT_RESPONSE], debug=debug) - query.get_data(0) - - carlog.warning("ecu disabled") - return True - - except Exception: - carlog.exception("ecu disable exception") - - carlog.error(f"ecu disable retry ({i + 1}) ...") - carlog.error("ecu disable failed") - return False - - -if __name__ == "__main__": - import time - import cereal.messaging as messaging - sendcan = messaging.pub_sock('sendcan') - logcan = messaging.sub_sock('can') - time.sleep(1) - - # honda bosch radar disable - disabled = disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03', timeout=0.5, debug=False) - print(f"disabled: {disabled}") diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 7bf6a6ad22293b..f807fc320edbe0 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -1,72 +1,13 @@ #!/usr/bin/env python3 import argparse -from collections import defaultdict -import jinja2 import os -from enum import Enum -from natsort import natsorted -from cereal import car from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car import gen_empty_fingerprint -from openpilot.selfdrive.car.docs_definitions import CarDocs, Column, CommonFootnote, PartType -from openpilot.selfdrive.car.car_helpers import interfaces, get_interface_attr -from openpilot.selfdrive.car.values import PLATFORMS - - -def get_all_footnotes() -> dict[Enum, int]: - all_footnotes = list(CommonFootnote) - for footnotes in get_interface_attr("Footnote", ignore_none=True).values(): - all_footnotes.extend(footnotes) - return {fn: idx + 1 for idx, fn in enumerate(all_footnotes)} - +from opendbc.car.docs import get_all_car_docs, generate_cars_md CARS_MD_OUT = os.path.join(BASEDIR, "docs", "CARS.md") CARS_MD_TEMPLATE = os.path.join(BASEDIR, "selfdrive", "car", "CARS_template.md") - -def get_all_car_docs() -> list[CarDocs]: - all_car_docs: list[CarDocs] = [] - footnotes = get_all_footnotes() - for model, platform in PLATFORMS.items(): - car_docs = platform.config.car_docs - # If available, uses experimental longitudinal limits for the docs - CP = interfaces[model][0].get_params(platform, fingerprint=gen_empty_fingerprint(), - car_fw=[car.CarParams.CarFw(ecu="unknown")], experimental_long=True, docs=True) - - if CP.dashcamOnly or not len(car_docs): - continue - - # A platform can include multiple car models - for _car_docs in car_docs: - if not hasattr(_car_docs, "row"): - _car_docs.init_make(CP) - _car_docs.init(CP, footnotes) - all_car_docs.append(_car_docs) - - # Sort cars by make and model + year - sorted_cars: list[CarDocs] = natsorted(all_car_docs, key=lambda car: car.name.lower()) - return sorted_cars - - -def group_by_make(all_car_docs: list[CarDocs]) -> dict[str, list[CarDocs]]: - sorted_car_docs = defaultdict(list) - for car_docs in all_car_docs: - sorted_car_docs[car_docs.make].append(car_docs) - return dict(sorted_car_docs) - - -def generate_cars_md(all_car_docs: list[CarDocs], template_fn: str) -> str: - with open(template_fn) as f: - template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) - - footnotes = [fn.value.text for fn in get_all_footnotes()] - cars_md: str = template.render(all_car_docs=all_car_docs, PartType=PartType, - group_by_make=group_by_make, footnotes=footnotes, - Column=Column) - return cars_md - - if __name__ == "__main__": parser = argparse.ArgumentParser(description="Auto generates supported cars documentation", formatter_class=argparse.ArgumentDefaultsHelpFormatter) diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py deleted file mode 100644 index f039fea9ac3ccc..00000000000000 --- a/selfdrive/car/docs_definitions.py +++ /dev/null @@ -1,368 +0,0 @@ -import re -from collections import namedtuple -import copy -from dataclasses import dataclass, field -from enum import Enum - -from cereal import car -from openpilot.selfdrive.car.conversions import Conversions as CV - -GOOD_TORQUE_THRESHOLD = 1.0 # m/s^2 -MODEL_YEARS_RE = r"(?<= )((\d{4}-\d{2})|(\d{4}))(,|$)" - - -class Column(Enum): - MAKE = "Make" - MODEL = "Model" - PACKAGE = "Supported Package" - LONGITUDINAL = "ACC" - FSR_LONGITUDINAL = "No ACC accel below" - FSR_STEERING = "No ALC below" - STEERING_TORQUE = "Steering Torque" - AUTO_RESUME = "Resume from stop" - HARDWARE = "Hardware Needed" - VIDEO = "Video" - - -class Star(Enum): - FULL = "full" - HALF = "half" - EMPTY = "empty" - - -# A part + its comprised parts -@dataclass -class BasePart: - name: str - parts: list[Enum] = field(default_factory=list) - - def all_parts(self): - # Recursively get all parts - _parts = 'parts' - parts = [] - parts.extend(getattr(self, _parts)) - for part in getattr(self, _parts): - parts.extend(part.value.all_parts()) - - return parts - - -class EnumBase(Enum): - @property - def part_type(self): - return PartType(self.__class__) - - -class Mount(EnumBase): - mount = BasePart("mount") - angled_mount_8_degrees = BasePart("angled mount (8 degrees)") - - -class Cable(EnumBase): - rj45_cable_7ft = BasePart("RJ45 cable (7 ft)") - long_obdc_cable = BasePart("long OBD-C cable") - usb_a_2_a_cable = BasePart("USB A-A cable") - usbc_otg_cable = BasePart("USB C OTG cable") - usbc_coupler = BasePart("USB-C coupler") - obd_c_cable_1_5ft = BasePart("OBD-C cable (1.5 ft)") - right_angle_obd_c_cable_1_5ft = BasePart("right angle OBD-C cable (1.5 ft)") - - -class Accessory(EnumBase): - harness_box = BasePart("harness box") - comma_power_v2 = BasePart("comma power v2") - - -@dataclass -class BaseCarHarness(BasePart): - parts: list[Enum] = field(default_factory=lambda: [Accessory.harness_box, Accessory.comma_power_v2, Cable.rj45_cable_7ft]) - has_connector: bool = True # without are hidden on the harness connector page - - -class CarHarness(EnumBase): - nidec = BaseCarHarness("Honda Nidec connector") - bosch_a = BaseCarHarness("Honda Bosch A connector") - bosch_b = BaseCarHarness("Honda Bosch B connector") - toyota_a = BaseCarHarness("Toyota A connector") - toyota_b = BaseCarHarness("Toyota B connector") - subaru_a = BaseCarHarness("Subaru A connector") - subaru_b = BaseCarHarness("Subaru B connector") - subaru_c = BaseCarHarness("Subaru C connector") - subaru_d = BaseCarHarness("Subaru D connector") - fca = BaseCarHarness("FCA connector") - ram = BaseCarHarness("Ram connector") - vw_a = BaseCarHarness("VW A connector") - vw_j533 = BaseCarHarness("VW J533 connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) - hyundai_a = BaseCarHarness("Hyundai A connector") - hyundai_b = BaseCarHarness("Hyundai B connector") - hyundai_c = BaseCarHarness("Hyundai C connector") - hyundai_d = BaseCarHarness("Hyundai D connector") - hyundai_e = BaseCarHarness("Hyundai E connector") - hyundai_f = BaseCarHarness("Hyundai F connector") - hyundai_g = BaseCarHarness("Hyundai G connector") - hyundai_h = BaseCarHarness("Hyundai H connector") - hyundai_i = BaseCarHarness("Hyundai I connector") - hyundai_j = BaseCarHarness("Hyundai J connector") - hyundai_k = BaseCarHarness("Hyundai K connector") - hyundai_l = BaseCarHarness("Hyundai L connector") - hyundai_m = BaseCarHarness("Hyundai M connector") - hyundai_n = BaseCarHarness("Hyundai N connector") - hyundai_o = BaseCarHarness("Hyundai O connector") - hyundai_p = BaseCarHarness("Hyundai P connector") - hyundai_q = BaseCarHarness("Hyundai Q connector") - hyundai_r = BaseCarHarness("Hyundai R connector") - custom = BaseCarHarness("Developer connector") - obd_ii = BaseCarHarness("OBD-II connector", parts=[Cable.long_obdc_cable, Cable.long_obdc_cable], has_connector=False) - gm = BaseCarHarness("GM connector", parts=[Accessory.harness_box]) - nissan_a = BaseCarHarness("Nissan A connector", parts=[Accessory.harness_box, Cable.rj45_cable_7ft, Cable.long_obdc_cable, Cable.usbc_coupler]) - nissan_b = BaseCarHarness("Nissan B connector", parts=[Accessory.harness_box, Cable.rj45_cable_7ft, Cable.long_obdc_cable, Cable.usbc_coupler]) - mazda = BaseCarHarness("Mazda connector") - ford_q3 = BaseCarHarness("Ford Q3 connector") - ford_q4 = BaseCarHarness("Ford Q4 connector", parts=[Accessory.harness_box, Accessory.comma_power_v2, Cable.rj45_cable_7ft, Cable.long_obdc_cable, - Cable.usbc_coupler]) - - -class Device(EnumBase): - threex = BasePart("comma 3X", parts=[Mount.mount, Cable.right_angle_obd_c_cable_1_5ft]) - # variant of comma 3X with angled mounts - threex_angled_mount = BasePart("comma 3X", parts=[Mount.angled_mount_8_degrees, Cable.right_angle_obd_c_cable_1_5ft]) - red_panda = BasePart("red panda") - - -class Kit(EnumBase): - red_panda_kit = BasePart("CAN FD panda kit", parts=[Device.red_panda, Accessory.harness_box, - Cable.usb_a_2_a_cable, Cable.usbc_otg_cable, Cable.obd_c_cable_1_5ft]) - - -class Tool(EnumBase): - socket_8mm_deep = BasePart("Socket Wrench 8mm or 5/16\" (deep)") - pry_tool = BasePart("Pry Tool") - - -class PartType(Enum): - accessory = Accessory - cable = Cable - connector = CarHarness - device = Device - kit = Kit - mount = Mount - tool = Tool - - -DEFAULT_CAR_PARTS: list[EnumBase] = [Device.threex] - - -@dataclass -class CarParts: - parts: list[EnumBase] = field(default_factory=list) - - def __call__(self): - return copy.deepcopy(self) - - @classmethod - def common(cls, add: list[EnumBase] = None, remove: list[EnumBase] = None): - p = [part for part in (add or []) + DEFAULT_CAR_PARTS if part not in (remove or [])] - return cls(p) - - def all_parts(self): - parts = [] - for part in self.parts: - parts.extend(part.value.all_parts()) - return self.parts + parts - - -CarFootnote = namedtuple("CarFootnote", ["text", "column", "docs_only", "shop_footnote"], defaults=(False, False)) - - -class CommonFootnote(Enum): - EXP_LONG_AVAIL = CarFootnote( - "openpilot Longitudinal Control (Alpha) is available behind a toggle; " + - "the toggle is only available in non-release branches such as `devel` or `master-ci`.", - Column.LONGITUDINAL, docs_only=True) - EXP_LONG_DSU = CarFootnote( - "By default, this car will use the stock Adaptive Cruise Control (ACC) for longitudinal control. " + - "If the Driver Support Unit (DSU) is disconnected, openpilot ACC will replace " + - "stock ACC. NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).", - Column.LONGITUDINAL) - - -def get_footnotes(footnotes: list[Enum], column: Column) -> list[Enum]: - # Returns applicable footnotes given current column - return [fn for fn in footnotes if fn.value.column == column] - - -# TODO: store years as a list -def get_year_list(years): - years_list = [] - if len(years) == 0: - return years_list - - for year in years.split(','): - year = year.strip() - if len(year) == 4: - years_list.append(str(year)) - elif "-" in year and len(year) == 7: - start, end = year.split("-") - years_list.extend(map(str, range(int(start), int(f"20{end}") + 1))) - else: - raise Exception(f"Malformed year string: {years}") - return years_list - - -def split_name(name: str) -> tuple[str, str, str]: - make, model = name.split(" ", 1) - years = "" - match = re.search(MODEL_YEARS_RE, model) - if match is not None: - years = model[match.start():] - model = model[:match.start() - 1] - return make, model, years - - -@dataclass -class CarDocs: - # make + model + model years - name: str - - # Example for Toyota Corolla MY20 - # requirements: Lane Tracing Assist (LTA) and Dynamic Radar Cruise Control (DRCC) - # US Market reference: "All", since all Corolla in the US come standard with LTA and DRCC - - # the simplest description of the requirements for the US market - package: str - - # the minimum compatibility requirements for this model, regardless - # of market. can be a package, trim, or list of features - requirements: str | None = None - - video_link: str | None = None - footnotes: list[Enum] = field(default_factory=list) - min_steer_speed: float | None = None - min_enable_speed: float | None = None - auto_resume: bool | None = None - - # all the parts needed for the supported car - car_parts: CarParts = field(default_factory=CarParts) - - def __post_init__(self): - self.make, self.model, self.years = split_name(self.name) - self.year_list = get_year_list(self.years) - - def init(self, CP: car.CarParams, all_footnotes: dict[Enum, int]): - self.car_name = CP.carName - self.car_fingerprint = CP.carFingerprint - - # longitudinal column - op_long = "Stock" - if CP.experimentalLongitudinalAvailable or CP.enableDsu: - op_long = "openpilot available" - if CP.enableDsu: - self.footnotes.append(CommonFootnote.EXP_LONG_DSU) - else: - self.footnotes.append(CommonFootnote.EXP_LONG_AVAIL) - elif CP.openpilotLongitudinalControl and not CP.enableDsu: - op_long = "openpilot" - - # min steer & enable speed columns - # TODO: set all the min steer speeds in carParams and remove this - if self.min_steer_speed is not None: - assert CP.minSteerSpeed < 0.5, f"{CP.carFingerprint}: Minimum steer speed set in both CarDocs and CarParams" - else: - self.min_steer_speed = CP.minSteerSpeed - - # TODO: set all the min enable speeds in carParams correctly and remove this - if self.min_enable_speed is None: - self.min_enable_speed = CP.minEnableSpeed - - if self.auto_resume is None: - self.auto_resume = CP.autoResumeSng and self.min_enable_speed <= 0 - - # hardware column - hardware_col = "None" - if self.car_parts.parts: - model_years = self.model + (' ' + self.years if self.years else '') - buy_link = f'Buy Here' - - tools_docs = [part for part in self.car_parts.all_parts() if isinstance(part, Tool)] - parts_docs = [part for part in self.car_parts.all_parts() if not isinstance(part, Tool)] - - def display_func(parts): - return '
'.join([f"- {parts.count(part)} {part.value.name}" for part in sorted(set(parts), key=lambda part: str(part.value.name))]) - - hardware_col = f'
Parts{display_func(parts_docs)}
{buy_link}
' - if len(tools_docs): - hardware_col += f'
Tools{display_func(tools_docs)}
' - - self.row: dict[Enum, str | Star] = { - Column.MAKE: self.make, - Column.MODEL: self.model, - Column.PACKAGE: self.package, - Column.LONGITUDINAL: op_long, - Column.FSR_LONGITUDINAL: f"{max(self.min_enable_speed * CV.MS_TO_MPH, 0):.0f} mph", - Column.FSR_STEERING: f"{max(self.min_steer_speed * CV.MS_TO_MPH, 0):.0f} mph", - Column.STEERING_TORQUE: Star.EMPTY, - Column.AUTO_RESUME: Star.FULL if self.auto_resume else Star.EMPTY, - Column.HARDWARE: hardware_col, - Column.VIDEO: self.video_link if self.video_link is not None else "", # replaced with an image and link from template in get_column - } - - # Set steering torque star from max lateral acceleration - assert CP.maxLateralAccel > 0.1 - if CP.maxLateralAccel >= GOOD_TORQUE_THRESHOLD: - self.row[Column.STEERING_TORQUE] = Star.FULL - - self.all_footnotes = all_footnotes - self.detail_sentence = self.get_detail_sentence(CP) - - return self - - def init_make(self, CP: car.CarParams): - """CarDocs subclasses can add make-specific logic for harness selection, footnotes, etc.""" - - def get_detail_sentence(self, CP): - if not CP.notCar: - sentence_builder = "openpilot upgrades your {car_model} with automated lane centering{alc} and adaptive cruise control{acc}." - - if self.min_steer_speed > self.min_enable_speed: - alc = f" above {self.min_steer_speed * CV.MS_TO_MPH:.0f} mph," if self.min_steer_speed > 0 else " at all speeds," - else: - alc = "" - - # Exception for cars which do not auto-resume yet - acc = "" - if self.min_enable_speed > 0: - acc = f" while driving above {self.min_enable_speed * CV.MS_TO_MPH:.0f} mph" - elif self.auto_resume: - acc = " that automatically resumes from a stop" - - if self.row[Column.STEERING_TORQUE] != Star.FULL: - sentence_builder += " This car may not be able to take tight turns on its own." - - # experimental mode - exp_link = "Experimental mode" - if CP.openpilotLongitudinalControl and not CP.experimentalLongitudinalAvailable: - sentence_builder += f" Traffic light and stop sign handling is also available in {exp_link}." - - return sentence_builder.format(car_model=f"{self.make} {self.model}", alc=alc, acc=acc) - - else: - if CP.carFingerprint == "COMMA_BODY": - return "The body is a robotics dev kit that can run openpilot. Learn more." - else: - raise Exception(f"This notCar does not have a detail sentence: {CP.carFingerprint}") - - def get_column(self, column: Column, star_icon: str, video_icon: str, footnote_tag: str) -> str: - item: str | Star = self.row[column] - if isinstance(item, Star): - item = star_icon.format(item.value) - elif column == Column.MODEL and len(self.years): - item += f" {self.years}" - elif column == Column.VIDEO and len(item) > 0: - item = video_icon.format(item) - - footnotes = get_footnotes(self.footnotes, column) - if len(footnotes): - sups = sorted([self.all_footnotes[fn] for fn in footnotes]) - item += footnote_tag.format(f'{",".join(map(str, sups))}') - - return item diff --git a/selfdrive/car/ecu_addrs.py b/selfdrive/car/ecu_addrs.py deleted file mode 100755 index 336d0d55429329..00000000000000 --- a/selfdrive/car/ecu_addrs.py +++ /dev/null @@ -1,95 +0,0 @@ -#!/usr/bin/env python3 -import capnp -import time - -from panda.python.uds import SERVICE_TYPE -from openpilot.selfdrive.car import make_tester_present_msg, carlog -from openpilot.selfdrive.car.can_definitions import CanRecvCallable, CanSendCallable -from openpilot.selfdrive.car.fw_query_definitions import EcuAddrBusType - - -def _is_tester_present_response(msg: capnp.lib.capnp._DynamicStructReader, subaddr: int = None) -> bool: - # ISO-TP messages are always padded to 8 bytes - # tester present response is always a single frame - dat_offset = 1 if subaddr is not None else 0 - if len(msg.dat) == 8 and 1 <= msg.dat[dat_offset] <= 7: - # success response - if msg.dat[dat_offset + 1] == (SERVICE_TYPE.TESTER_PRESENT + 0x40): - return True - # error response - if msg.dat[dat_offset + 1] == 0x7F and msg.dat[dat_offset + 2] == SERVICE_TYPE.TESTER_PRESENT: - return True - return False - - -def _get_all_ecu_addrs(can_recv: CanRecvCallable, can_send: CanSendCallable, bus: int, timeout: float = 1, debug: bool = True) -> set[EcuAddrBusType]: - addr_list = [0x700 + i for i in range(256)] + [0x18da00f1 + (i << 8) for i in range(256)] - queries: set[EcuAddrBusType] = {(addr, None, bus) for addr in addr_list} - responses = queries - return get_ecu_addrs(can_recv, can_send, queries, responses, timeout=timeout, debug=debug) - - -def get_ecu_addrs(can_recv: CanRecvCallable, can_send: CanSendCallable, queries: set[EcuAddrBusType], - responses: set[EcuAddrBusType], timeout: float = 1, debug: bool = False) -> set[EcuAddrBusType]: - ecu_responses: set[EcuAddrBusType] = set() # set((addr, subaddr, bus),) - try: - msgs = [make_tester_present_msg(addr, bus, subaddr) for addr, subaddr, bus in queries] - - can_recv() - can_send(msgs) - start_time = time.monotonic() - while time.monotonic() - start_time < timeout: - can_packets = can_recv(wait_for_one=True) - for packet in can_packets: - for msg in packet: - if not len(msg.dat): - carlog.warning("ECU addr scan: skipping empty remote frame") - continue - - subaddr = None if (msg.address, None, msg.src) in responses else msg.dat[0] - if (msg.address, subaddr, msg.src) in responses and _is_tester_present_response(msg, subaddr): - if debug: - print(f"CAN-RX: {hex(msg.address)} - 0x{bytes.hex(msg.dat)}") - if (msg.address, subaddr, msg.src) in ecu_responses: - print(f"Duplicate ECU address: {hex(msg.address)}") - ecu_responses.add((msg.address, subaddr, msg.src)) - except Exception: - carlog.exception("ECU addr scan exception") - return ecu_responses - - -if __name__ == "__main__": - import argparse - import cereal.messaging as messaging - from openpilot.common.params import Params - from openpilot.selfdrive.car.card import obd_callback - - parser = argparse.ArgumentParser(description='Get addresses of all ECUs') - parser.add_argument('--debug', action='store_true') - parser.add_argument('--bus', type=int, default=1) - parser.add_argument('--no-obd', action='store_true') - parser.add_argument('--timeout', type=float, default=1.0) - args = parser.parse_args() - - logcan = messaging.sub_sock('can') - sendcan = messaging.pub_sock('sendcan') - - # Set up params for pandad - params = Params() - params.remove("FirmwareQueryDone") - params.put_bool("IsOnroad", False) - time.sleep(0.2) # thread is 10 Hz - params.put_bool("IsOnroad", True) - - obd_callback(params)(not args.no_obd) - - print("Getting ECU addresses ...") - ecu_addrs = _get_all_ecu_addrs(logcan, sendcan, args.bus, args.timeout, debug=args.debug) - - print() - print("Found ECUs on rx addresses:") - for addr, subaddr, _ in ecu_addrs: - msg = f" {hex(addr)}" - if subaddr is not None: - msg += f" (sub-address: {hex(subaddr)})" - print(msg) diff --git a/selfdrive/car/filter_simple.py b/selfdrive/car/filter_simple.py deleted file mode 100644 index 0ec7a515621afb..00000000000000 --- a/selfdrive/car/filter_simple.py +++ /dev/null @@ -1,18 +0,0 @@ -class FirstOrderFilter: - # first order filter - def __init__(self, x0, rc, dt, initialized=True): - self.x = x0 - self.dt = dt - self.update_alpha(rc) - self.initialized = initialized - - def update_alpha(self, rc): - self.alpha = self.dt / (rc + self.dt) - - def update(self, x): - if self.initialized: - self.x = (1. - self.alpha) * self.x + self.alpha * x - else: - self.initialized = True - self.x = x - return self.x diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py deleted file mode 100644 index dc93c38246804d..00000000000000 --- a/selfdrive/car/fingerprints.py +++ /dev/null @@ -1,348 +0,0 @@ -from openpilot.selfdrive.car.interfaces import get_interface_attr -from openpilot.selfdrive.car.body.values import CAR as BODY -from openpilot.selfdrive.car.chrysler.values import CAR as CHRYSLER -from openpilot.selfdrive.car.ford.values import CAR as FORD -from openpilot.selfdrive.car.gm.values import CAR as GM -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.hyundai.values import CAR as HYUNDAI -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.subaru.values import CAR as SUBARU -from openpilot.selfdrive.car.tesla.values import CAR as TESLA -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.volkswagen.values import CAR as VW - -FW_VERSIONS = get_interface_attr('FW_VERSIONS', combine_brands=True, ignore_none=True) -_FINGERPRINTS = get_interface_attr('FINGERPRINTS', combine_brands=True, ignore_none=True) - -_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes - - -def is_valid_for_fingerprint(msg, car_fingerprint: dict[int, int]): - adr = msg.address - # ignore addresses that are more than 11 bits - return (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) or adr >= 0x800 - - -def eliminate_incompatible_cars(msg, candidate_cars): - """Removes cars that could not have sent msg. - - Inputs: - msg: A cereal/log CanData message from the car. - candidate_cars: A list of cars to consider. - - Returns: - A list containing the subset of candidate_cars that could have sent msg. - """ - compatible_cars = [] - - for car_name in candidate_cars: - car_fingerprints = _FINGERPRINTS[car_name] - - for fingerprint in car_fingerprints: - # add alien debug address - if is_valid_for_fingerprint(msg, fingerprint | _DEBUG_ADDRESS): - compatible_cars.append(car_name) - break - - return compatible_cars - - -def all_known_cars(): - """Returns a list of all known car strings.""" - return list({*FW_VERSIONS.keys(), *_FINGERPRINTS.keys()}) - - -def all_legacy_fingerprint_cars(): - """Returns a list of all known car strings, FPv1 only.""" - return list(_FINGERPRINTS.keys()) - - -# A dict that maps old platform strings to their latest representations -MIGRATION = { - "ACURA ILX 2016 ACURAWATCH PLUS": HONDA.ACURA_ILX, - "ACURA RDX 2018 ACURAWATCH PLUS": HONDA.ACURA_RDX, - "ACURA RDX 2020 TECH": HONDA.ACURA_RDX_3G, - "AUDI A3": VW.AUDI_A3_MK3, - "HONDA ACCORD 2018 HYBRID TOURING": HONDA.HONDA_ACCORD, - "HONDA ACCORD 1.5T 2018": HONDA.HONDA_ACCORD, - "HONDA ACCORD 2018 LX 1.5T": HONDA.HONDA_ACCORD, - "HONDA ACCORD 2018 SPORT 2T": HONDA.HONDA_ACCORD, - "HONDA ACCORD 2T 2018": HONDA.HONDA_ACCORD, - "HONDA ACCORD HYBRID 2018": HONDA.HONDA_ACCORD, - "HONDA CIVIC 2016 TOURING": HONDA.HONDA_CIVIC, - "HONDA CIVIC HATCHBACK 2017 SEDAN/COUPE 2019": HONDA.HONDA_CIVIC_BOSCH, - "HONDA CIVIC SEDAN 1.6 DIESEL": HONDA.HONDA_CIVIC_BOSCH_DIESEL, - "HONDA CR-V 2016 EXECUTIVE": HONDA.HONDA_CRV_EU, - "HONDA CR-V 2016 TOURING": HONDA.HONDA_CRV, - "HONDA CR-V 2017 EX": HONDA.HONDA_CRV_5G, - "HONDA CR-V 2019 HYBRID": HONDA.HONDA_CRV_HYBRID, - "HONDA FIT 2018 EX": HONDA.HONDA_FIT, - "HONDA HRV 2019 TOURING": HONDA.HONDA_HRV, - "HONDA INSIGHT 2019 TOURING": HONDA.HONDA_INSIGHT, - "HONDA ODYSSEY 2018 EX-L": HONDA.HONDA_ODYSSEY, - "HONDA ODYSSEY 2019 EXCLUSIVE CHN": HONDA.HONDA_ODYSSEY_CHN, - "HONDA PILOT 2017 TOURING": HONDA.HONDA_PILOT, - "HONDA PILOT 2019 ELITE": HONDA.HONDA_PILOT, - "HONDA PILOT 2019": HONDA.HONDA_PILOT, - "HONDA PASSPORT 2021": HONDA.HONDA_PILOT, - "HONDA RIDGELINE 2017 BLACK EDITION": HONDA.HONDA_RIDGELINE, - "HYUNDAI ELANTRA LIMITED ULTIMATE 2017": HYUNDAI.HYUNDAI_ELANTRA, - "HYUNDAI SANTA FE LIMITED 2019": HYUNDAI.HYUNDAI_SANTA_FE, - "HYUNDAI TUCSON DIESEL 2019": HYUNDAI.HYUNDAI_TUCSON, - "KIA OPTIMA 2016": HYUNDAI.KIA_OPTIMA_G4, - "KIA OPTIMA 2019": HYUNDAI.KIA_OPTIMA_G4_FL, - "KIA OPTIMA SX 2019 & 2016": HYUNDAI.KIA_OPTIMA_G4_FL, - "LEXUS CT 200H 2018": TOYOTA.LEXUS_CTH, - "LEXUS ES 300H 2018": TOYOTA.LEXUS_ES, - "LEXUS ES 300H 2019": TOYOTA.LEXUS_ES_TSS2, - "LEXUS IS300 2018": TOYOTA.LEXUS_IS, - "LEXUS NX300 2018": TOYOTA.LEXUS_NX, - "LEXUS NX300H 2018": TOYOTA.LEXUS_NX, - "LEXUS RX 350 2016": TOYOTA.LEXUS_RX, - "LEXUS RX350 2020": TOYOTA.LEXUS_RX_TSS2, - "LEXUS RX450 HYBRID 2020": TOYOTA.LEXUS_RX_TSS2, - "TOYOTA SIENNA XLE 2018": TOYOTA.TOYOTA_SIENNA, - "TOYOTA C-HR HYBRID 2018": TOYOTA.TOYOTA_CHR, - "TOYOTA COROLLA HYBRID TSS2 2019": TOYOTA.TOYOTA_COROLLA_TSS2, - "TOYOTA RAV4 HYBRID 2019": TOYOTA.TOYOTA_RAV4_TSS2, - "LEXUS ES HYBRID 2019": TOYOTA.LEXUS_ES_TSS2, - "LEXUS NX HYBRID 2018": TOYOTA.LEXUS_NX, - "LEXUS NX HYBRID 2020": TOYOTA.LEXUS_NX_TSS2, - "LEXUS RX HYBRID 2020": TOYOTA.LEXUS_RX_TSS2, - "TOYOTA ALPHARD HYBRID 2021": TOYOTA.TOYOTA_ALPHARD_TSS2, - "TOYOTA AVALON HYBRID 2019": TOYOTA.TOYOTA_AVALON_2019, - "TOYOTA AVALON HYBRID 2022": TOYOTA.TOYOTA_AVALON_TSS2, - "TOYOTA CAMRY HYBRID 2018": TOYOTA.TOYOTA_CAMRY, - "TOYOTA CAMRY HYBRID 2021": TOYOTA.TOYOTA_CAMRY_TSS2, - "TOYOTA C-HR HYBRID 2022": TOYOTA.TOYOTA_CHR_TSS2, - "TOYOTA HIGHLANDER HYBRID 2020": TOYOTA.TOYOTA_HIGHLANDER_TSS2, - "TOYOTA RAV4 HYBRID 2022": TOYOTA.TOYOTA_RAV4_TSS2_2022, - "TOYOTA RAV4 HYBRID 2023": TOYOTA.TOYOTA_RAV4_TSS2_2023, - "TOYOTA HIGHLANDER HYBRID 2018": TOYOTA.TOYOTA_HIGHLANDER, - "LEXUS ES HYBRID 2018": TOYOTA.LEXUS_ES, - "LEXUS RX HYBRID 2017": TOYOTA.LEXUS_RX, - "HYUNDAI TUCSON HYBRID 4TH GEN": HYUNDAI.HYUNDAI_TUCSON_4TH_GEN, - "KIA SPORTAGE HYBRID 5TH GEN": HYUNDAI.KIA_SPORTAGE_5TH_GEN, - "KIA SORENTO PLUG-IN HYBRID 4TH GEN": HYUNDAI.KIA_SORENTO_HEV_4TH_GEN, - "CADILLAC ESCALADE ESV PLATINUM 2019": GM.CADILLAC_ESCALADE_ESV_2019, - - # Removal of platform_str, see https://github.com/commaai/openpilot/pull/31868/ - "COMMA BODY": BODY.COMMA_BODY, - "CHRYSLER PACIFICA HYBRID 2017": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, - "CHRYSLER_PACIFICA_2017_HYBRID": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, - "CHRYSLER PACIFICA HYBRID 2018": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, - "CHRYSLER PACIFICA HYBRID 2019": CHRYSLER.CHRYSLER_PACIFICA_2019_HYBRID, - "CHRYSLER PACIFICA 2018": CHRYSLER.CHRYSLER_PACIFICA_2018, - "CHRYSLER PACIFICA 2020": CHRYSLER.CHRYSLER_PACIFICA_2020, - "DODGE DURANGO 2021": CHRYSLER.DODGE_DURANGO, - "JEEP GRAND CHEROKEE V6 2018": CHRYSLER.JEEP_GRAND_CHEROKEE, - "JEEP GRAND CHEROKEE 2019": CHRYSLER.JEEP_GRAND_CHEROKEE_2019, - "RAM 1500 5TH GEN": CHRYSLER.RAM_1500_5TH_GEN, - "RAM HD 5TH GEN": CHRYSLER.RAM_HD_5TH_GEN, - "FORD BRONCO SPORT 1ST GEN": FORD.FORD_BRONCO_SPORT_MK1, - "FORD ESCAPE 4TH GEN": FORD.FORD_ESCAPE_MK4, - "FORD EXPLORER 6TH GEN": FORD.FORD_EXPLORER_MK6, - "FORD F-150 14TH GEN": FORD.FORD_F_150_MK14, - "FORD F-150 LIGHTNING 1ST GEN": FORD.FORD_F_150_LIGHTNING_MK1, - "FORD FOCUS 4TH GEN": FORD.FORD_FOCUS_MK4, - "FORD MAVERICK 1ST GEN": FORD.FORD_MAVERICK_MK1, - "FORD MUSTANG MACH-E 1ST GEN": FORD.FORD_MUSTANG_MACH_E_MK1, - "HOLDEN ASTRA RS-V BK 2017": GM.HOLDEN_ASTRA, - "CHEVROLET VOLT PREMIER 2017": GM.CHEVROLET_VOLT, - "CADILLAC ATS Premium Performance 2018": GM.CADILLAC_ATS, - "CHEVROLET MALIBU PREMIER 2017": GM.CHEVROLET_MALIBU, - "GMC ACADIA DENALI 2018": GM.GMC_ACADIA, - "BUICK LACROSSE 2017": GM.BUICK_LACROSSE, - "BUICK REGAL ESSENCE 2018": GM.BUICK_REGAL, - "CADILLAC ESCALADE 2017": GM.CADILLAC_ESCALADE, - "CADILLAC ESCALADE ESV 2016": GM.CADILLAC_ESCALADE_ESV, - "CADILLAC ESCALADE ESV 2019": GM.CADILLAC_ESCALADE_ESV_2019, - "CHEVROLET BOLT EUV 2022": GM.CHEVROLET_BOLT_EUV, - "CHEVROLET SILVERADO 1500 2020": GM.CHEVROLET_SILVERADO, - "CHEVROLET EQUINOX 2019": GM.CHEVROLET_EQUINOX, - "CHEVROLET TRAILBLAZER 2021": GM.CHEVROLET_TRAILBLAZER, - "HONDA ACCORD 2018": HONDA.HONDA_ACCORD, - "HONDA CIVIC (BOSCH) 2019": HONDA.HONDA_CIVIC_BOSCH, - "HONDA CIVIC SEDAN 1.6 DIESEL 2019": HONDA.HONDA_CIVIC_BOSCH_DIESEL, - "HONDA CIVIC 2022": HONDA.HONDA_CIVIC_2022, - "HONDA CR-V 2017": HONDA.HONDA_CRV_5G, - "HONDA CR-V HYBRID 2019": HONDA.HONDA_CRV_HYBRID, - "HONDA HR-V 2023": HONDA.HONDA_HRV_3G, - "ACURA RDX 2020": HONDA.ACURA_RDX_3G, - "HONDA INSIGHT 2019": HONDA.HONDA_INSIGHT, - "HONDA E 2020": HONDA.HONDA_E, - "ACURA ILX 2016": HONDA.ACURA_ILX, - "HONDA CR-V 2016": HONDA.HONDA_CRV, - "HONDA CR-V EU 2016": HONDA.HONDA_CRV_EU, - "HONDA FIT 2018": HONDA.HONDA_FIT, - "HONDA FREED 2020": HONDA.HONDA_FREED, - "HONDA HRV 2019": HONDA.HONDA_HRV, - "HONDA ODYSSEY 2018": HONDA.HONDA_ODYSSEY, - "HONDA ODYSSEY CHN 2019": HONDA.HONDA_ODYSSEY_CHN, - "ACURA RDX 2018": HONDA.ACURA_RDX, - "HONDA PILOT 2017": HONDA.HONDA_PILOT, - "HONDA RIDGELINE 2017": HONDA.HONDA_RIDGELINE, - "HONDA CIVIC 2016": HONDA.HONDA_CIVIC, - "HYUNDAI AZERA 6TH GEN": HYUNDAI.HYUNDAI_AZERA_6TH_GEN, - "HYUNDAI AZERA HYBRID 6TH GEN": HYUNDAI.HYUNDAI_AZERA_HEV_6TH_GEN, - "HYUNDAI ELANTRA 2017": HYUNDAI.HYUNDAI_ELANTRA, - "HYUNDAI I30 N LINE 2019 & GT 2018 DCT": HYUNDAI.HYUNDAI_ELANTRA_GT_I30, - "HYUNDAI ELANTRA 2021": HYUNDAI.HYUNDAI_ELANTRA_2021, - "HYUNDAI ELANTRA HYBRID 2021": HYUNDAI.HYUNDAI_ELANTRA_HEV_2021, - "HYUNDAI GENESIS 2015-2016": HYUNDAI.HYUNDAI_GENESIS, - "HYUNDAI IONIQ HYBRID 2017-2019": HYUNDAI.HYUNDAI_IONIQ, - "HYUNDAI IONIQ HYBRID 2020-2022": HYUNDAI.HYUNDAI_IONIQ_HEV_2022, - "HYUNDAI IONIQ ELECTRIC LIMITED 2019": HYUNDAI.HYUNDAI_IONIQ_EV_LTD, - "HYUNDAI IONIQ ELECTRIC 2020": HYUNDAI.HYUNDAI_IONIQ_EV_2020, - "HYUNDAI IONIQ PLUG-IN HYBRID 2019": HYUNDAI.HYUNDAI_IONIQ_PHEV_2019, - "HYUNDAI IONIQ PHEV 2020": HYUNDAI.HYUNDAI_IONIQ_PHEV, - "HYUNDAI KONA 2020": HYUNDAI.HYUNDAI_KONA, - "HYUNDAI KONA ELECTRIC 2019": HYUNDAI.HYUNDAI_KONA_EV, - "HYUNDAI KONA ELECTRIC 2022": HYUNDAI.HYUNDAI_KONA_EV_2022, - "HYUNDAI KONA ELECTRIC 2ND GEN": HYUNDAI.HYUNDAI_KONA_EV_2ND_GEN, - "HYUNDAI KONA HYBRID 2020": HYUNDAI.HYUNDAI_KONA_HEV, - "HYUNDAI SANTA FE 2019": HYUNDAI.HYUNDAI_SANTA_FE, - "HYUNDAI SANTA FE 2022": HYUNDAI.HYUNDAI_SANTA_FE_2022, - "HYUNDAI SANTA FE HYBRID 2022": HYUNDAI.HYUNDAI_SANTA_FE_HEV_2022, - "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": HYUNDAI.HYUNDAI_SANTA_FE_PHEV_2022, - "HYUNDAI SONATA 2020": HYUNDAI.HYUNDAI_SONATA, - "HYUNDAI SONATA 2019": HYUNDAI.HYUNDAI_SONATA_LF, - "HYUNDAI STARIA 4TH GEN": HYUNDAI.HYUNDAI_STARIA_4TH_GEN, - "HYUNDAI TUCSON 2019": HYUNDAI.HYUNDAI_TUCSON, - "HYUNDAI PALISADE 2020": HYUNDAI.HYUNDAI_PALISADE, - "HYUNDAI VELOSTER 2019": HYUNDAI.HYUNDAI_VELOSTER, - "HYUNDAI SONATA HYBRID 2021": HYUNDAI.HYUNDAI_SONATA_HYBRID, - "HYUNDAI IONIQ 5 2022": HYUNDAI.HYUNDAI_IONIQ_5, - "HYUNDAI IONIQ 6 2023": HYUNDAI.HYUNDAI_IONIQ_6, - "HYUNDAI TUCSON 4TH GEN": HYUNDAI.HYUNDAI_TUCSON_4TH_GEN, - "HYUNDAI SANTA CRUZ 1ST GEN": HYUNDAI.HYUNDAI_SANTA_CRUZ_1ST_GEN, - "HYUNDAI CUSTIN 1ST GEN": HYUNDAI.HYUNDAI_CUSTIN_1ST_GEN, - "KIA FORTE E 2018 & GT 2021": HYUNDAI.KIA_FORTE, - "KIA K5 2021": HYUNDAI.KIA_K5_2021, - "KIA K5 HYBRID 2020": HYUNDAI.KIA_K5_HEV_2020, - "KIA K8 HYBRID 1ST GEN": HYUNDAI.KIA_K8_HEV_1ST_GEN, - "KIA NIRO EV 2020": HYUNDAI.KIA_NIRO_EV, - "KIA NIRO EV 2ND GEN": HYUNDAI.KIA_NIRO_EV_2ND_GEN, - "KIA NIRO HYBRID 2019": HYUNDAI.KIA_NIRO_PHEV, - "KIA NIRO PLUG-IN HYBRID 2022": HYUNDAI.KIA_NIRO_PHEV_2022, - "KIA NIRO HYBRID 2021": HYUNDAI.KIA_NIRO_HEV_2021, - "KIA NIRO HYBRID 2ND GEN": HYUNDAI.KIA_NIRO_HEV_2ND_GEN, - "KIA OPTIMA 4TH GEN": HYUNDAI.KIA_OPTIMA_G4, - "KIA OPTIMA 4TH GEN FACELIFT": HYUNDAI.KIA_OPTIMA_G4_FL, - "KIA OPTIMA HYBRID 2017 & SPORTS 2019": HYUNDAI.KIA_OPTIMA_H, - "KIA OPTIMA HYBRID 4TH GEN FACELIFT": HYUNDAI.KIA_OPTIMA_H_G4_FL, - "KIA SELTOS 2021": HYUNDAI.KIA_SELTOS, - "KIA SPORTAGE 5TH GEN": HYUNDAI.KIA_SPORTAGE_5TH_GEN, - "KIA SORENTO GT LINE 2018": HYUNDAI.KIA_SORENTO, - "KIA SORENTO 4TH GEN": HYUNDAI.KIA_SORENTO_4TH_GEN, - "KIA SORENTO HYBRID 4TH GEN": HYUNDAI.KIA_SORENTO_HEV_4TH_GEN, - "KIA STINGER GT2 2018": HYUNDAI.KIA_STINGER, - "KIA STINGER 2022": HYUNDAI.KIA_STINGER_2022, - "KIA CEED INTRO ED 2019": HYUNDAI.KIA_CEED, - "KIA EV6 2022": HYUNDAI.KIA_EV6, - "KIA CARNIVAL 4TH GEN": HYUNDAI.KIA_CARNIVAL_4TH_GEN, - "GENESIS GV60 ELECTRIC 1ST GEN": HYUNDAI.GENESIS_GV60_EV_1ST_GEN, - "GENESIS G70 2018": HYUNDAI.GENESIS_G70, - "GENESIS G70 2020": HYUNDAI.GENESIS_G70_2020, - "GENESIS GV70 1ST GEN": HYUNDAI.GENESIS_GV70_1ST_GEN, - "GENESIS G80 2017": HYUNDAI.GENESIS_G80, - "GENESIS G90 2017": HYUNDAI.GENESIS_G90, - "GENESIS GV80 2023": HYUNDAI.GENESIS_GV80, - "MAZDA CX-5": MAZDA.MAZDA_CX5, - "MAZDA CX-9": MAZDA.MAZDA_CX9, - "MAZDA 3": MAZDA.MAZDA_3, - "MAZDA 6": MAZDA.MAZDA_6, - "MAZDA CX-9 2021": MAZDA.MAZDA_CX9_2021, - "MAZDA CX-5 2022": MAZDA.MAZDA_CX5_2022, - "NISSAN X-TRAIL 2017": NISSAN.NISSAN_XTRAIL, - "NISSAN LEAF 2018": NISSAN.NISSAN_LEAF, - "NISSAN LEAF 2018 Instrument Cluster": NISSAN.NISSAN_LEAF_IC, - "NISSAN ROGUE 2019": NISSAN.NISSAN_ROGUE, - "NISSAN ALTIMA 2020": NISSAN.NISSAN_ALTIMA, - "SUBARU ASCENT LIMITED 2019": SUBARU.SUBARU_ASCENT, - "SUBARU OUTBACK 6TH GEN": SUBARU.SUBARU_OUTBACK, - "SUBARU LEGACY 7TH GEN": SUBARU.SUBARU_LEGACY, - "SUBARU IMPREZA LIMITED 2019": SUBARU.SUBARU_IMPREZA, - "SUBARU IMPREZA SPORT 2020": SUBARU.SUBARU_IMPREZA_2020, - "SUBARU CROSSTREK HYBRID 2020": SUBARU.SUBARU_CROSSTREK_HYBRID, - "SUBARU FORESTER 2019": SUBARU.SUBARU_FORESTER, - "SUBARU FORESTER HYBRID 2020": SUBARU.SUBARU_FORESTER_HYBRID, - "SUBARU FORESTER 2017 - 2018": SUBARU.SUBARU_FORESTER_PREGLOBAL, - "SUBARU LEGACY 2015 - 2018": SUBARU.SUBARU_LEGACY_PREGLOBAL, - "SUBARU OUTBACK 2015 - 2017": SUBARU.SUBARU_OUTBACK_PREGLOBAL, - "SUBARU OUTBACK 2018 - 2019": SUBARU.SUBARU_OUTBACK_PREGLOBAL_2018, - "SUBARU FORESTER 2022": SUBARU.SUBARU_FORESTER_2022, - "SUBARU OUTBACK 7TH GEN": SUBARU.SUBARU_OUTBACK_2023, - "SUBARU ASCENT 2023": SUBARU.SUBARU_ASCENT_2023, - 'TESLA AP1 MODEL S': TESLA.TESLA_AP1_MODELS, - 'TESLA AP2 MODEL S': TESLA.TESLA_AP2_MODELS, - 'TESLA MODEL S RAVEN': TESLA.TESLA_MODELS_RAVEN, - "TOYOTA ALPHARD 2020": TOYOTA.TOYOTA_ALPHARD_TSS2, - "TOYOTA AVALON 2016": TOYOTA.TOYOTA_AVALON, - "TOYOTA AVALON 2019": TOYOTA.TOYOTA_AVALON_2019, - "TOYOTA AVALON 2022": TOYOTA.TOYOTA_AVALON_TSS2, - "TOYOTA CAMRY 2018": TOYOTA.TOYOTA_CAMRY, - "TOYOTA CAMRY 2021": TOYOTA.TOYOTA_CAMRY_TSS2, - "TOYOTA C-HR 2018": TOYOTA.TOYOTA_CHR, - "TOYOTA C-HR 2021": TOYOTA.TOYOTA_CHR_TSS2, - "TOYOTA COROLLA 2017": TOYOTA.TOYOTA_COROLLA, - "TOYOTA COROLLA TSS2 2019": TOYOTA.TOYOTA_COROLLA_TSS2, - "TOYOTA HIGHLANDER 2017": TOYOTA.TOYOTA_HIGHLANDER, - "TOYOTA HIGHLANDER 2020": TOYOTA.TOYOTA_HIGHLANDER_TSS2, - "TOYOTA PRIUS 2017": TOYOTA.TOYOTA_PRIUS, - "TOYOTA PRIUS v 2017": TOYOTA.TOYOTA_PRIUS_V, - "TOYOTA PRIUS TSS2 2021": TOYOTA.TOYOTA_PRIUS_TSS2, - "TOYOTA RAV4 2017": TOYOTA.TOYOTA_RAV4, - "TOYOTA RAV4 HYBRID 2017": TOYOTA.TOYOTA_RAV4H, - "TOYOTA RAV4 2019": TOYOTA.TOYOTA_RAV4_TSS2, - "TOYOTA RAV4 2022": TOYOTA.TOYOTA_RAV4_TSS2_2022, - "TOYOTA RAV4 2023": TOYOTA.TOYOTA_RAV4_TSS2_2023, - "TOYOTA MIRAI 2021": TOYOTA.TOYOTA_MIRAI, - "TOYOTA SIENNA 2018": TOYOTA.TOYOTA_SIENNA, - "LEXUS CT HYBRID 2018": TOYOTA.LEXUS_CTH, - "LEXUS ES 2018": TOYOTA.LEXUS_ES, - "LEXUS ES 2019": TOYOTA.LEXUS_ES_TSS2, - "LEXUS IS 2018": TOYOTA.LEXUS_IS, - "LEXUS IS 2023": TOYOTA.LEXUS_IS_TSS2, - "LEXUS NX 2018": TOYOTA.LEXUS_NX, - "LEXUS NX 2020": TOYOTA.LEXUS_NX_TSS2, - "LEXUS LC 2024": TOYOTA.LEXUS_LC_TSS2, - "LEXUS RC 2020": TOYOTA.LEXUS_RC, - "LEXUS RX 2016": TOYOTA.LEXUS_RX, - "LEXUS RX 2020": TOYOTA.LEXUS_RX_TSS2, - "LEXUS GS F 2016": TOYOTA.LEXUS_GS_F, - "VOLKSWAGEN ARTEON 1ST GEN": VW.VOLKSWAGEN_ARTEON_MK1, - "VOLKSWAGEN ATLAS 1ST GEN": VW.VOLKSWAGEN_ATLAS_MK1, - "VOLKSWAGEN CADDY 3RD GEN": VW.VOLKSWAGEN_CADDY_MK3, - "VOLKSWAGEN CRAFTER 2ND GEN": VW.VOLKSWAGEN_CRAFTER_MK2, - "VOLKSWAGEN GOLF 7TH GEN": VW.VOLKSWAGEN_GOLF_MK7, - "VOLKSWAGEN JETTA 7TH GEN": VW.VOLKSWAGEN_JETTA_MK7, - "VOLKSWAGEN PASSAT 8TH GEN": VW.VOLKSWAGEN_PASSAT_MK8, - "VOLKSWAGEN PASSAT NMS": VW.VOLKSWAGEN_PASSAT_NMS, - "VOLKSWAGEN POLO 6TH GEN": VW.VOLKSWAGEN_POLO_MK6, - "VOLKSWAGEN SHARAN 2ND GEN": VW.VOLKSWAGEN_SHARAN_MK2, - "VOLKSWAGEN TAOS 1ST GEN": VW.VOLKSWAGEN_TAOS_MK1, - "VOLKSWAGEN T-CROSS 1ST GEN": VW.VOLKSWAGEN_TCROSS_MK1, - "VOLKSWAGEN TIGUAN 2ND GEN": VW.VOLKSWAGEN_TIGUAN_MK2, - "VOLKSWAGEN TOURAN 2ND GEN": VW.VOLKSWAGEN_TOURAN_MK2, - "VOLKSWAGEN TRANSPORTER T6.1": VW.VOLKSWAGEN_TRANSPORTER_T61, - "VOLKSWAGEN T-ROC 1ST GEN": VW.VOLKSWAGEN_TROC_MK1, - "AUDI A3 3RD GEN": VW.AUDI_A3_MK3, - "AUDI Q2 1ST GEN": VW.AUDI_Q2_MK1, - "AUDI Q3 2ND GEN": VW.AUDI_Q3_MK2, - "SEAT ATECA 1ST GEN": VW.SEAT_ATECA_MK1, - "SEAT LEON 3RD GEN": VW.SEAT_ATECA_MK1, - "SEAT_LEON_MK3": VW.SEAT_ATECA_MK1, - "SKODA FABIA 4TH GEN": VW.SKODA_FABIA_MK4, - "SKODA KAMIQ 1ST GEN": VW.SKODA_KAMIQ_MK1, - "SKODA KAROQ 1ST GEN": VW.SKODA_KAROQ_MK1, - "SKODA KODIAQ 1ST GEN": VW.SKODA_KODIAQ_MK1, - "SKODA OCTAVIA 3RD GEN": VW.SKODA_OCTAVIA_MK3, - "SKODA SCALA 1ST GEN": VW.SKODA_KAMIQ_MK1, - "SKODA_SCALA_MK1": VW.SKODA_KAMIQ_MK1, - "SKODA SUPERB 3RD GEN": VW.SKODA_SUPERB_MK3, - - "mock": MOCK.MOCK, -} diff --git a/selfdrive/car/ford/__init__.py b/selfdrive/car/ford/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py deleted file mode 100644 index 961d7086c44b9a..00000000000000 --- a/selfdrive/car/ford/carcontroller.py +++ /dev/null @@ -1,118 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.ford import fordcan -from openpilot.selfdrive.car.ford.values import CarControllerParams, FordFlags -from openpilot.selfdrive.car.helpers import clip -from openpilot.selfdrive.car.interfaces import CarControllerBase, V_CRUISE_MAX - -LongCtrlState = car.CarControl.Actuators.LongControlState -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw): - # No blending at low speed due to lack of torque wind-up and inaccurate current curvature - if v_ego_raw > 9: - apply_curvature = clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR, - current_curvature + CarControllerParams.CURVATURE_ERROR) - - # Curvature rate limit after driver torque limit - apply_curvature = apply_std_steer_angle_limits(apply_curvature, apply_curvature_last, v_ego_raw, CarControllerParams) - - return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX) - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.packer = CANPacker(dbc_name) - self.CAN = fordcan.CanBus(CP) - - self.apply_curvature_last = 0 - self.main_on_last = False - self.lkas_enabled_last = False - self.steer_alert_last = False - self.lead_distance_bars_last = None - - def update(self, CC, CS, now_nanos): - can_sends = [] - - actuators = CC.actuators - hud_control = CC.hudControl - - main_on = CS.out.cruiseState.available - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - - ### acc buttons ### - if CC.cruiseControl.cancel: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, cancel=True)) - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, cancel=True)) - elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, resume=True)) - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, resume=True)) - # if stock lane centering isn't off, send a button press to toggle it off - # the stock system checks for steering pressed, and eventually disengages cruise control - elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, tja_toggle=True)) - - ### lateral control ### - # send steer msg at 20Hz - if (self.frame % CarControllerParams.STEER_STEP) == 0: - if CC.latActive: - # apply rate limits, curvature error limit, and clip to signal range - current_curvature = -CS.out.yawRate / max(CS.out.vEgoRaw, 0.1) - apply_curvature = apply_ford_curvature_limits(actuators.curvature, self.apply_curvature_last, current_curvature, CS.out.vEgoRaw) - else: - apply_curvature = 0. - - self.apply_curvature_last = apply_curvature - - if self.CP.flags & FordFlags.CANFD: - # TODO: extended mode - mode = 1 if CC.latActive else 0 - counter = (self.frame // CarControllerParams.STEER_STEP) % 0x10 - can_sends.append(fordcan.create_lat_ctl2_msg(self.packer, self.CAN, mode, 0., 0., -apply_curvature, 0., counter)) - else: - can_sends.append(fordcan.create_lat_ctl_msg(self.packer, self.CAN, CC.latActive, 0., 0., -apply_curvature, 0.)) - - # send lka msg at 33Hz - if (self.frame % CarControllerParams.LKA_STEP) == 0: - can_sends.append(fordcan.create_lka_msg(self.packer, self.CAN)) - - ### longitudinal control ### - # send acc msg at 50Hz - if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0: - # Both gas and accel are in m/s^2, accel is used solely for braking - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - gas = accel - if not CC.longActive or gas < CarControllerParams.MIN_GAS: - gas = CarControllerParams.INACTIVE_GAS - stopping = CC.actuators.longControlState == LongCtrlState.stopping - # TODO: look into using the actuators packet to send the desired speed - can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, v_ego_kph=V_CRUISE_MAX)) - - ### ui ### - send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) - # send lkas ui msg at 1Hz or if ui state changes - if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_lkas_ui_msg(self.packer, self.CAN, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values)) - - # send acc ui msg at 5Hz or if ui state changes - if hud_control.leadDistanceBars != self.lead_distance_bars_last: - send_ui = True - if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_acc_ui_msg(self.packer, self.CAN, self.CP, main_on, CC.latActive, - fcw_alert, CS.out.cruiseState.standstill, hud_control, - CS.acc_tja_status_stock_values)) - - self.main_on_last = main_on - self.lkas_enabled_last = CC.latActive - self.steer_alert_last = steer_alert - self.lead_distance_bars_last = hud_control.leadDistanceBars - - new_actuators = actuators.as_builder() - new_actuators.curvature = self.apply_curvature_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py deleted file mode 100644 index ed707a5f78553b..00000000000000 --- a/selfdrive/car/ford/carstate.py +++ /dev/null @@ -1,174 +0,0 @@ -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import DBC, CarControllerParams, FordFlags -from openpilot.selfdrive.car.interfaces import CarStateBase - -GearShifter = car.CarState.GearShifter -TransmissionType = car.CarParams.TransmissionType - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["PowertrainData_10"]["TrnRng_D_Rq"] - - self.vehicle_sensors_valid = False - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - # Occasionally on startup, the ABS module recalibrates the steering pinion offset, so we need to block engagement - # The vehicle usually recovers out of this state within a minute of normal driving - self.vehicle_sensors_valid = cp.vl["SteeringPinion_Data"]["StePinCompAnEst_D_Qf"] == 3 - - # car speed - ret.vEgoRaw = cp.vl["BrakeSysFeatures"]["Veh_V_ActlBrk"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] - ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 - - # gas pedal - ret.gas = cp.vl["EngVehicleSpThrottle"]["ApedPos_Pc_ActlArb"] / 100. - ret.gasPressed = ret.gas > 1e-6 - - # brake pedal - ret.brake = cp.vl["BrakeSnData_4"]["BrkTot_Tq_Actl"] / 32756. # torque in Nm - ret.brakePressed = cp.vl["EngBrakeData"]["BpedDrvAppl_D_Actl"] == 2 - ret.parkingBrake = cp.vl["DesiredTorqBrk"]["PrkBrkStatus"] in (1, 2) - - # steering wheel - ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] - ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5) - ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 - ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) - ret.espDisabled = cp.vl["Cluster_Info1_FD1"]["DrvSlipCtlMde_D_Rq"] != 0 # 0 is default mode - - if self.CP.flags & FordFlags.CANFD: - # this signal is always 0 on non-CAN FD cars - ret.steerFaultTemporary |= cp.vl["Lane_Assist_Data3_FD1"]["LatCtlSte_D_Stat"] not in (1, 2, 3) - - # cruise state - is_metric = cp.vl["INSTRUMENT_PANEL"]["METRIC_UNITS"] == 1 if not self.CP.flags & FordFlags.CANFD else False - ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * (CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS) - ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) - ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) - ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0 - ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3 - ret.accFaulted = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (1, 2) - if not self.CP.openpilotLongitudinalControl: - ret.accFaulted = ret.accFaulted or cp_cam.vl["ACCDATA"]["CmbbDeny_B_Actl"] == 1 - - # gear - if self.CP.transmissionType == TransmissionType.automatic: - gear = self.shifter_values.get(cp.vl["PowertrainData_10"]["TrnRng_D_Rq"]) - ret.gearShifter = self.parse_gear_shifter(gear) - elif self.CP.transmissionType == TransmissionType.manual: - ret.clutchPressed = cp.vl["Engine_Clutch_Data"]["CluPdlPos_Pc_Meas"] > 0 - if bool(cp.vl["BCM_Lamp_Stat_FD1"]["RvrseLghtOn_B_Stat"]): - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # safety - ret.stockFcw = bool(cp_cam.vl["ACCDATA_3"]["FcwVisblWarn_B_Rq"]) - ret.stockAeb = bool(cp_cam.vl["ACCDATA_2"]["CmbbBrkDecel_B_Rq"]) - - # button presses - ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 - ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 - # TODO: block this going to the camera otherwise it will enable stock TJA - ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["Steering_Data_FD1"]["AccButtnGapTogglePress"] - - # lock info - ret.doorOpen = any([cp.vl["BodyInfo_3_FD1"]["DrStatDrv_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatPsngr_B_Actl"], - cp.vl["BodyInfo_3_FD1"]["DrStatRl_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatRr_B_Actl"]]) - ret.seatbeltUnlatched = cp.vl["RCMStatusMessage2_FD1"]["FirstRowBuckleDriver"] == 2 - - # blindspot sensors - if self.CP.enableBsm: - cp_bsm = cp_cam if self.CP.flags & FordFlags.CANFD else cp - ret.leftBlindspot = cp_bsm.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 - ret.rightBlindspot = cp_bsm.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 - - # Stock steering buttons so that we can passthru blinkers etc. - self.buttons_stock_values = cp.vl["Steering_Data_FD1"] - # Stock values from IPMA so that we can retain some stock functionality - self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] - self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("VehicleOperatingModes", 100), - ("BrakeSysFeatures", 50), - ("Yaw_Data_FD1", 100), - ("DesiredTorqBrk", 50), - ("EngVehicleSpThrottle", 100), - ("BrakeSnData_4", 50), - ("EngBrakeData", 10), - ("Cluster_Info1_FD1", 10), - ("SteeringPinion_Data", 100), - ("EPAS_INFO", 50), - ("Steering_Data_FD1", 10), - ("BodyInfo_3_FD1", 2), - ("RCMStatusMessage2_FD1", 10), - ] - - if CP.flags & FordFlags.CANFD: - messages += [ - ("Lane_Assist_Data3_FD1", 33), - ] - else: - messages += [ - ("INSTRUMENT_PANEL", 1), - ] - - if CP.transmissionType == TransmissionType.automatic: - messages += [ - ("PowertrainData_10", 10), - ] - elif CP.transmissionType == TransmissionType.manual: - messages += [ - ("Engine_Clutch_Data", 33), - ("BCM_Lamp_Stat_FD1", 1), - ] - - if CP.enableBsm and not (CP.flags & FordFlags.CANFD): - messages += [ - ("Side_Detect_L_Stat", 5), - ("Side_Detect_R_Stat", 5), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).main) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - # sig_address, frequency - ("ACCDATA", 50), - ("ACCDATA_2", 50), - ("ACCDATA_3", 5), - ("IPMA_Data", 1), - ] - - if CP.enableBsm and CP.flags & FordFlags.CANFD: - messages += [ - ("Side_Detect_L_Stat", 5), - ("Side_Detect_R_Stat", 5), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) diff --git a/selfdrive/car/ford/fingerprints.py b/selfdrive/car/ford/fingerprints.py deleted file mode 100644 index 2201072fa3a29d..00000000000000 --- a/selfdrive/car/ford/fingerprints.py +++ /dev/null @@ -1,166 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.ford.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.FORD_BRONCO_SPORT_MK1: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1PT-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_ESCAPE_MK4: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_EXPLORER_MK6: { - (Ecu.eps, 0x730, None): [ - b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'P1MC-14D003-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_F_150_MK14: { - (Ecu.eps, 0x730, None): [ - b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABR\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_F_150_LIGHTNING_MK1: { - (Ecu.abs, 0x760, None): [ - b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_MUSTANG_MACH_E_MK1: { - (Ecu.eps, 0x730, None): [ - b'LJ9C-14D003-AM\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ9C-14D003-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LK9C-2D053-CK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABS\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_FOCUS_MK4: { - (Ecu.eps, 0x730, None): [ - b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_MAVERICK_MK1: { - (Ecu.eps, 0x730, None): [ - b'NZ6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'NZ6C-2D053-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-EE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-EF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_RANGER_MK2: { - (Ecu.eps, 0x730, None): [ - b'NL14-14D003-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PB3C-2D053-ZD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py deleted file mode 100644 index 5bb3d0570ff5de..00000000000000 --- a/selfdrive/car/ford/fordcan.py +++ /dev/null @@ -1,340 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car import CanBusBase - -HUDControl = car.CarControl.HUDControl - - -class CanBus(CanBusBase): - def __init__(self, CP=None, fingerprint=None) -> None: - super().__init__(CP, fingerprint) - - @property - def main(self) -> int: - return self.offset - - @property - def radar(self) -> int: - return self.offset + 1 - - @property - def camera(self) -> int: - return self.offset + 2 - - -def calculate_lat_ctl2_checksum(mode: int, counter: int, dat: bytearray) -> int: - curvature = (dat[2] << 3) | ((dat[3]) >> 5) - curvature_rate = (dat[6] << 3) | ((dat[7]) >> 5) - path_angle = ((dat[3] & 0x1F) << 6) | ((dat[4]) >> 2) - path_offset = ((dat[4] & 0x3) << 8) | dat[5] - - checksum = mode + counter - for sig_val in (curvature, curvature_rate, path_angle, path_offset): - checksum += sig_val + (sig_val >> 8) - - return 0xFF - (checksum & 0xFF) - - -def create_lka_msg(packer, CAN: CanBus): - """ - Creates an empty CAN message for the Ford LKA Command. - - This command can apply "Lane Keeping Aid" maneuvers, which are subject to the PSCM lockout. - - Frequency is 33Hz. - """ - - return packer.make_can_msg("Lane_Assist_Data1", CAN.main, {}) - - -def create_lat_ctl_msg(packer, CAN: CanBus, lat_active: bool, path_offset: float, path_angle: float, curvature: float, - curvature_rate: float): - """ - Creates a CAN message for the Ford TJA/LCA Command. - - This command can apply "Lane Centering" maneuvers: continuous lane centering for traffic jam assist and highway - driving. It is not subject to the PSCM lockout. - - Ford lane centering command uses a third order polynomial to describe the road centerline. The polynomial is defined - by the following coefficients: - c0: lateral offset between the vehicle and the centerline (positive is right) - c1: heading angle between the vehicle and the centerline (positive is right) - c2: curvature of the centerline (positive is left) - c3: rate of change of curvature of the centerline - As the PSCM combines this information with other sensor data, such as the vehicle's yaw rate and speed, the steering - angle cannot be easily controlled. - - The PSCM should be configured to accept TJA/LCA commands before these commands will be processed. This can be done - using tools such as Forscan. - - Frequency is 20Hz. - """ - - values = { - "LatCtlRng_L_Max": 0, # Unknown [0|126] meter - "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1] - "LatCtl_D_Rq": 1 if lat_active else 0, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, - # 3=InterventionRight, 4-7=NotUsed [0|7] - "LatCtlRampType_D_Rq": 0, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] - # Makes no difference with curvature control - "LatCtlPrecision_D_Rq": 1, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] - # The stock system always uses comfortable - "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians - "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2 - "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter - } - return packer.make_can_msg("LateralMotionControl", CAN.main, values) - - -def create_lat_ctl2_msg(packer, CAN: CanBus, mode: int, path_offset: float, path_angle: float, curvature: float, - curvature_rate: float, counter: int): - """ - Create a CAN message for the new Ford Lane Centering command. - - This message is used on the CAN FD platform and replaces the old LateralMotionControl message. It is similar but has - additional signals for a counter and checksum. - - Frequency is 20Hz. - """ - - values = { - "LatCtl_D2_Rq": mode, # Mode: 0=None, 1=PathFollowingLimitedMode, 2=PathFollowingExtendedMode, - # 3=SafeRampOut, 4-7=NotUsed [0|7] - "LatCtlRampType_D_Rq": 0, # 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] - "LatCtlPrecision_D_Rq": 1, # 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] - "LatCtlPathOffst_L_Actl": path_offset, # [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # [-0.5|0.5235] radians - "LatCtlCurv_No_Actl": curvature, # [-0.02|0.02094] 1/meter - "LatCtlCrv_NoRate2_Actl": curvature_rate, # [-0.001024|0.001023] 1/meter^2 - "HandsOffCnfm_B_Rq": 0, # 0=Inactive, 1=Active [0|1] - "LatCtlPath_No_Cnt": counter, # [0|15] - "LatCtlPath_No_Cs": 0, # [0|255] - } - - # calculate checksum - dat = packer.make_can_msg("LateralMotionControl2", 0, values)[1] - values["LatCtlPath_No_Cs"] = calculate_lat_ctl2_checksum(mode, counter, dat) - - return packer.make_can_msg("LateralMotionControl2", CAN.main, values) - - -def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, v_ego_kph: float): - """ - Creates a CAN message for the Ford ACC Command. - - This command can be used to enable ACC, to set the ACC gas/brake/decel values - and to disable ACC. - - Frequency is 50Hz. - """ - decel = accel < 0 and long_active - values = { - "AccBrkTot_A_Rq": accel, # Brake total accel request: [-20|11.9449] m/s^2 - "Cmbb_B_Enbl": 1 if long_active else 0, # Enabled: 0=No, 1=Yes - "AccPrpl_A_Rq": gas, # Acceleration request: [-5|5.23] m/s^2 - "AccPrpl_A_Pred": -5.0, # Acceleration request: [-5|5.23] m/s^2 - "AccResumEnbl_B_Rq": 1 if long_active else 0, - "AccVeh_V_Trg": v_ego_kph, # Target speed: [0|255] km/h - # TODO: we may be able to improve braking response by utilizing pre-charging better - "AccBrkPrchg_B_Rq": 1 if decel else 0, # Pre-charge brake request: 0=No, 1=Yes - "AccBrkDecel_B_Rq": 1 if decel else 0, # Deceleration request: 0=Inactive, 1=Active - "AccStopStat_B_Rq": 1 if stopping else 0, - } - return packer.make_can_msg("ACCDATA", CAN.main, values) - - -def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw_alert: bool, standstill: bool, - hud_control, stock_values: dict): - """ - Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam - assist status. - - Stock functionality is maintained by passing through unmodified signals. - - Frequency is 5Hz. - """ - - # Tja_D_Stat - if enabled: - if hud_control.leftLaneDepart: - status = 3 # ActiveInterventionLeft - elif hud_control.rightLaneDepart: - status = 4 # ActiveInterventionRight - else: - status = 2 # Active - elif main_on: - if hud_control.leftLaneDepart: - status = 5 # ActiveWarningLeft - elif hud_control.rightLaneDepart: - status = 6 # ActiveWarningRight - else: - status = 1 # Standby - else: - status = 0 # Off - - values = {s: stock_values[s] for s in [ - "HaDsply_No_Cs", - "HaDsply_No_Cnt", - "AccStopStat_D_Dsply", # ACC stopped status message - "AccTrgDist2_D_Dsply", # ACC target distance - "AccStopRes_B_Dsply", - "TjaWarn_D_Rq", # TJA warning - "TjaMsgTxt_D_Dsply", # TJA text - "IaccLamp_D_Rq", # iACC status icon - "AccMsgTxt_D2_Rq", # ACC text - "FcwDeny_B_Dsply", # FCW disabled - "FcwMemStat_B_Actl", # FCW enabled setting - "AccTGap_B_Dsply", # ACC time gap display setting - "CadsAlignIncplt_B_Actl", - "AccFllwMde_B_Dsply", # ACC follow mode display setting - "CadsRadrBlck_B_Actl", - "CmbbPostEvnt_B_Dsply", # AEB event status - "AccStopMde_B_Dsply", # ACC stop mode display setting - "FcwMemSens_D_Actl", # FCW sensitivity setting - "FcwMsgTxt_D_Rq", # FCW text - "AccWarn_D_Dsply", # ACC warning - "FcwVisblWarn_B_Rq", # FCW visible alert - "FcwAudioWarn_B_Rq", # FCW audio alert - "AccTGap_D_Dsply", # ACC time gap - "AccMemEnbl_B_RqDrv", # ACC adaptive/normal setting - "FdaMem_B_Stat", # FDA enabled setting - ]} - - values.update({ - "Tja_D_Stat": status, # TJA status - }) - - if CP.openpilotLongitudinalControl: - values.update({ - "AccStopStat_D_Dsply": 2 if standstill else 0, # Stopping status text - "AccMsgTxt_D2_Rq": 0, # ACC text - "AccTGap_B_Dsply": 0, # Show time gap control UI - "AccFllwMde_B_Dsply": 1 if hud_control.leadVisible else 0, # Lead indicator - "AccStopMde_B_Dsply": 1 if standstill else 0, - "AccWarn_D_Dsply": 0, # ACC warning - "AccTGap_D_Dsply": hud_control.leadDistanceBars, # Time gap - }) - - # Forwards FCW alert from IPMA - if fcw_alert: - values["FcwVisblWarn_B_Rq"] = 1 # FCW visible alert - - return packer.make_can_msg("ACCDATA_3", CAN.main, values) - - -def create_lkas_ui_msg(packer, CAN: CanBus, main_on: bool, enabled: bool, steer_alert: bool, hud_control, - stock_values: dict): - """ - Creates a CAN message for the Ford IPC IPMA/LKAS status. - - Show the LKAS status with the "driver assist" lines in the IPC. - - Stock functionality is maintained by passing through unmodified signals. - - Frequency is 1Hz. - """ - - # LaActvStats_D_Dsply - # R Intvn Warn Supprs Avail No - # L - # Intvn 24 19 14 9 4 - # Warn 23 18 13 8 3 - # Supprs 22 17 12 7 2 - # Avail 21 16 11 6 1 - # No 20 15 10 5 0 - # - # TODO: test suppress state - if enabled: - lines = 0 # NoLeft_NoRight - if hud_control.leftLaneDepart: - lines += 4 - elif hud_control.leftLaneVisible: - lines += 1 - if hud_control.rightLaneDepart: - lines += 20 - elif hud_control.rightLaneVisible: - lines += 5 - elif main_on: - lines = 0 - else: - if hud_control.leftLaneDepart: - lines = 3 # WarnLeft_NoRight - elif hud_control.rightLaneDepart: - lines = 15 # NoLeft_WarnRight - else: - lines = 30 # LA_Off - - hands_on_wheel_dsply = 1 if steer_alert else 0 - - values = {s: stock_values[s] for s in [ - "FeatConfigIpmaActl", - "FeatNoIpmaActl", - "PersIndexIpma_D_Actl", - "AhbcRampingV_D_Rq", # AHB ramping - "LaDenyStats_B_Dsply", # LKAS error - "CamraDefog_B_Req", # Windshield heater? - "CamraStats_D_Dsply", # Camera status - "DasAlrtLvl_D_Dsply", # DAS alert level - "DasStats_D_Dsply", # DAS status - "DasWarn_D_Dsply", # DAS warning - "AhbHiBeam_D_Rq", # AHB status - "Passthru_63", - "Passthru_48", - ]} - - values.update({ - "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] - "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed - }) - return packer.make_can_msg("IPMA_Data", CAN.main, values) - - -def create_button_msg(packer, bus: int, stock_values: dict, cancel=False, resume=False, tja_toggle=False): - """ - Creates a CAN message for the Ford SCCM buttons/switches. - - Includes cruise control buttons, turn lights and more. - - Frequency is 10Hz. - """ - - values = {s: stock_values[s] for s in [ - "HeadLghtHiFlash_D_Stat", # SCCM Passthrough the remaining buttons - "TurnLghtSwtch_D_Stat", # SCCM Turn signal switch - "WiprFront_D_Stat", - "LghtAmb_D_Sns", - "AccButtnGapDecPress", - "AccButtnGapIncPress", - "AslButtnOnOffCnclPress", - "AslButtnOnOffPress", - "LaSwtchPos_D_Stat", - "CcAslButtnCnclResPress", - "CcAslButtnDeny_B_Actl", - "CcAslButtnIndxDecPress", - "CcAslButtnIndxIncPress", - "CcAslButtnOffCnclPress", - "CcAslButtnOnOffCncl", - "CcAslButtnOnPress", - "CcAslButtnResDecPress", - "CcAslButtnResIncPress", - "CcAslButtnSetDecPress", - "CcAslButtnSetIncPress", - "CcAslButtnSetPress", - "CcButtnOffPress", - "CcButtnOnOffCnclPress", - "CcButtnOnOffPress", - "CcButtnOnPress", - "HeadLghtHiFlash_D_Actl", - "HeadLghtHiOn_B_StatAhb", - "AhbStat_B_Dsply", - "AccButtnGapTogglePress", - "WiprFrontSwtch_D_Stat", - "HeadLghtHiCtrl_D_RqAhb", - ]} - - values.update({ - "CcAslButtnCnclPress": 1 if cancel else 0, # CC cancel button - "CcAsllButtnResPress": 1 if resume else 0, # CC resume button - "TjaButtnOnOffPress": 1 if tja_toggle else 0, # LCA/TJA toggle button - }) - return packer.make_can_msg("Steering_Data_FD1", bus, values) diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py deleted file mode 100644 index b872be212b19fe..00000000000000 --- a/selfdrive/car/ford/interface.py +++ /dev/null @@ -1,81 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import Ecu, FordFlags -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -TransmissionType = car.CarParams.TransmissionType -GearShifter = car.CarState.GearShifter - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "ford" - ret.dashcamOnly = bool(ret.flags & FordFlags.CANFD) - - ret.radarUnavailable = True - ret.steerControlType = car.CarParams.SteerControlType.angle - ret.steerActuatorDelay = 0.2 - ret.steerLimitTimer = 1.0 - - CAN = CanBus(fingerprint=fingerprint) - cfgs = [get_safety_config(car.CarParams.SafetyModel.ford)] - if CAN.main >= 4: - cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) - ret.safetyConfigs = cfgs - - ret.experimentalLongitudinalAvailable = True - if experimental_long: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_LONG_CONTROL - ret.openpilotLongitudinalControl = True - - if ret.flags & FordFlags.CANFD: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_CANFD - else: - # Lock out if the car does not have needed lateral and longitudinal control APIs. - # Note that we also check CAN for adaptive cruise, but no known signal for LCA exists - pscm_config = next((fw for fw in car_fw if fw.ecu == Ecu.eps and b'\x22\xDE\x01' in fw.request), None) - if pscm_config: - if len(pscm_config.fwVersion) != 24: - ret.dashcamOnly = True - else: - config_tja = pscm_config.fwVersion[7] # Traffic Jam Assist - config_lca = pscm_config.fwVersion[8] # Lane Centering Assist - if config_tja != 0xFF or config_lca != 0xFF: - ret.dashcamOnly = True - - # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 - found_ecus = [fw.ecu for fw in car_fw] - if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[CAN.main] or docs: - ret.transmissionType = TransmissionType.automatic - else: - ret.transmissionType = TransmissionType.manual - ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS - - # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat - # TODO: detect bsm in car_fw? - ret.enableBsm = 0x3A6 in fingerprint[CAN.main] and 0x3A7 in fingerprint[CAN.main] - - # LCA can steer down to zero - ret.minSteerSpeed = 0. - - ret.autoResumeSng = ret.minEnableSpeed == -1. - ret.centerToFront = ret.wheelbase * 0.44 - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - events = self.create_common_events(ret, extra_gears=[GearShifter.manumatic]) - if not self.CS.vehicle_sensors_valid: - events.add(car.CarEvent.EventName.vehicleSensorsInvalid) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py deleted file mode 100644 index f405373661925f..00000000000000 --- a/selfdrive/car/ford/radar_interface.py +++ /dev/null @@ -1,143 +0,0 @@ -from math import cos, sin -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import DBC, RADAR -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) - -DELPHI_MRR_RADAR_START_ADDR = 0x120 -DELPHI_MRR_RADAR_MSG_COUNT = 64 - - -def _create_delphi_esr_radar_can_parser(CP) -> CANParser: - msg_n = len(DELPHI_ESR_RADAR_MSGS) - messages = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n, strict=True)) - - return CANParser(RADAR.DELPHI_ESR, messages, CanBus(CP).radar) - - -def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: - messages = [] - - for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): - msg = f"MRR_Detection_{i:03d}" - messages += [(msg, 20)] - - return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - self.updated_messages = set() - self.track_id = 0 - self.radar = DBC[CP.carFingerprint]['radar'] - if self.radar is None or CP.radarUnavailable: - self.rcp = None - elif self.radar == RADAR.DELPHI_ESR: - self.rcp = _create_delphi_esr_radar_can_parser(CP) - self.trigger_msg = DELPHI_ESR_RADAR_MSGS[-1] - self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} - elif self.radar == RADAR.DELPHI_MRR: - self.rcp = _create_delphi_mrr_radar_can_parser(CP) - self.trigger_msg = DELPHI_MRR_RADAR_START_ADDR + DELPHI_MRR_RADAR_MSG_COUNT - 1 - else: - raise ValueError(f"Unsupported radar: {self.radar}") - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - if self.radar == RADAR.DELPHI_ESR: - self._update_delphi_esr() - elif self.radar == RADAR.DELPHI_MRR: - self._update_delphi_mrr() - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret - - def _update_delphi_esr(self): - for ii in sorted(self.updated_messages): - cpt = self.rcp.vl[ii] - - if cpt['X_Rel'] > 0.00001: - self.valid_cnt[ii] = 0 # reset counter - - if cpt['X_Rel'] > 0.00001: - self.valid_cnt[ii] += 1 - else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - #print ii, self.valid_cnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] - - # radar point only valid if there have been enough valid measurements - if self.valid_cnt[ii] > 0: - if ii not in self.pts: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['X_Rel'] # from front of car - self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * CV.DEG_TO_RAD # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['V_Rel'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] - - def _update_delphi_mrr(self): - for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): - msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] - - # SCAN_INDEX rotates through 0..3 on each message - # treat these as separate points - scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] - i = (ii - 1) * 4 + scanIndex - - if i not in self.pts: - self.pts[i] = car.RadarData.RadarPoint.new_message() - self.pts[i].trackId = self.track_id - self.pts[i].aRel = float('nan') - self.pts[i].yvRel = float('nan') - self.track_id += 1 - - valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) - - if valid: - azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] - dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] - distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] - dRel = cos(azimuth) * dist # m from front of car - yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive - - # delphi doesn't notify of track switches, so do it manually - # TODO: refactor this to radard if more radars behave this way - if abs(self.pts[i].vRel - distRate) > 2 or abs(self.pts[i].dRel - dRel) > 5: - self.track_id += 1 - self.pts[i].trackId = self.track_id - - self.pts[i].dRel = dRel - self.pts[i].yRel = yRel - self.pts[i].vRel = distRate - - self.pts[i].measured = True - - else: - del self.pts[i] diff --git a/selfdrive/car/ford/tests/__init__.py b/selfdrive/car/ford/tests/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/ford/tests/print_platform_codes.py b/selfdrive/car/ford/tests/print_platform_codes.py deleted file mode 100755 index 670199980a6838..00000000000000 --- a/selfdrive/car/ford/tests/print_platform_codes.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict - -from cereal import car -from openpilot.selfdrive.car.ford.values import get_platform_codes -from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -if __name__ == "__main__": - cars_for_code: defaultdict = defaultdict(lambda: defaultdict(set)) - - for car_model, ecus in FW_VERSIONS.items(): - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - platform_codes = get_platform_codes(ecus[ecu]) - for code in platform_codes: - cars_for_code[ecu][code].add(car_model) - - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {sorted(platform_codes)}') - print() - - print('\nCar models vs. platform codes:') - for ecu, codes in cars_for_code.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - for code, cars in codes.items(): - print(f' {code!r}: {sorted(map(str, cars))}') diff --git a/selfdrive/car/ford/tests/test_ford.py b/selfdrive/car/ford/tests/test_ford.py deleted file mode 100644 index b1a19017d401b0..00000000000000 --- a/selfdrive/car/ford/tests/test_ford.py +++ /dev/null @@ -1,143 +0,0 @@ -import random -from collections.abc import Iterable - -import capnp -from hypothesis import settings, given, strategies as st -from parameterized import parameterized - -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.ford.values import CAR, FW_QUERY_CONFIG, FW_PATTERN, get_platform_codes -from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - - -ECU_ADDRESSES = { - Ecu.eps: 0x730, # Power Steering Control Module (PSCM) - Ecu.abs: 0x760, # Anti-Lock Brake System (ABS) - Ecu.fwdRadar: 0x764, # Cruise Control Module (CCM) - Ecu.fwdCamera: 0x706, # Image Processing Module A (IPMA) - Ecu.engine: 0x7E0, # Powertrain Control Module (PCM) - Ecu.shiftByWire: 0x732, # Gear Shift Module (GSM) - Ecu.debug: 0x7D0, # Accessory Protocol Interface Module (APIM) -} - - -ECU_PART_NUMBER = { - Ecu.eps: [ - b"14D003", - ], - Ecu.abs: [ - b"2D053", - ], - Ecu.fwdRadar: [ - b"14D049", - ], - Ecu.fwdCamera: [ - b"14F397", # Ford Q3 - b"14H102", # Ford Q4 - ], -} - - -class TestFordFW: - def test_fw_query_config(self): - for (ecu, addr, subaddr) in FW_QUERY_CONFIG.extra_ecus: - assert ecu in ECU_ADDRESSES, "Unknown ECU" - assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" - assert subaddr is None, "Unexpected ECU subaddress" - - @parameterized.expand(FW_VERSIONS.items()) - def test_fw_versions(self, car_model: str, fw_versions: dict[tuple[capnp.lib.capnp._EnumModule, int, int | None], Iterable[bytes]]): - for (ecu, addr, subaddr), fws in fw_versions.items(): - assert ecu in ECU_PART_NUMBER, "Unexpected ECU" - assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" - assert subaddr is None, "Unexpected ECU subaddress" - - for fw in fws: - assert len(fw) == 24, "Expected ECU response to be 24 bytes" - - match = FW_PATTERN.match(fw) - assert match is not None, f"Unable to parse FW: {fw!r}" - if match: - part_number = match.group("part_number") - assert part_number in ECU_PART_NUMBER[ecu], f"Unexpected part number for {fw!r}" - - codes = get_platform_codes([fw]) - assert 1 == len(codes), f"Unable to parse FW: {fw!r}" - - @settings(max_examples=100) - @given(data=st.data()) - def test_platform_codes_fuzzy_fw(self, data): - """Ensure function doesn't raise an exception""" - fw_strategy = st.lists(st.binary()) - fws = data.draw(fw_strategy) - get_platform_codes(fws) - - def test_platform_codes_spot_check(self): - # Asserts basic platform code parsing behavior for a few cases - results = get_platform_codes([ - b"JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ]) - assert results == {(b"X6A", b"J"), (b"Z6T", b"N"), (b"J6T", b"P"), (b"B5A", b"L")} - - def test_fuzzy_match(self): - for platform, fw_by_addr in FW_VERSIONS.items(): - # Ensure there's no overlaps in platform codes - for _ in range(20): - car_fw = [] - for ecu, fw_versions in fw_by_addr.items(): - ecu_name, addr, sub_addr = ecu - fw = random.choice(fw_versions) - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) - - CP = car.CarParams.new_message(carFw=car_fw) - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) - assert matches == {platform} - - def test_match_fw_fuzzy(self): - offline_fw = { - (Ecu.eps, 0x730, None): [ - b"L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - (Ecu.abs, 0x760, None): [ - b"L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - (Ecu.fwdRadar, 0x764, None): [ - b"LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"LB5T-14D049-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - # We consider all model year hints for ECU, even with different platform codes - (Ecu.fwdCamera, 0x706, None): [ - b"LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"NC5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - } - expected_fingerprint = CAR.FORD_EXPLORER_MK6 - - # ensure that we fuzzy match on all non-exact FW with changed revisions - live_fw = { - (0x730, None): {b"L1MC-14D003-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - (0x760, None): {b"L1MC-2D053-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - (0x764, None): {b"LB5T-14D049-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - (0x706, None): {b"LB5T-14F397-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - } - candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw}) - assert candidates == {expected_fingerprint} - - # model year hint in between the range should match - live_fw[(0x706, None)] = {b"MB5T-14F397-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"} - candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw,}) - assert candidates == {expected_fingerprint} - - # unseen model year hint should not match - live_fw[(0x760, None)] = {b"M1MC-2D053-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"} - candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw}) - assert len(candidates) == 0, "Should not match new model year hint" diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py deleted file mode 100644 index b1868bfa9bb97d..00000000000000 --- a/selfdrive/car/ford/values.py +++ /dev/null @@ -1,279 +0,0 @@ -import copy -import re -from dataclasses import dataclass, field, replace -from enum import Enum, IntFlag - -import panda.python.uds as uds -from cereal import car -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, dbc_dict, DbcDict, PlatformConfig, Platforms -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, LiveFwVersions, OfflineFwVersions, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - STEER_STEP = 5 # LateralMotionControl, 20Hz - LKA_STEP = 3 # Lane_Assist_Data1, 33Hz - ACC_CONTROL_STEP = 2 # ACCDATA, 50Hz - LKAS_UI_STEP = 100 # IPMA_Data, 1Hz - ACC_UI_STEP = 20 # ACCDATA_3, 5Hz - BUTTONS_STEP = 5 # Steering_Data_FD1, 10Hz, but send twice as fast - - CURVATURE_MAX = 0.02 # Max curvature for steering command, m^-1 - STEER_DRIVER_ALLOWANCE = 1.0 # Driver intervention threshold, Nm - - # Curvature rate limits - # The curvature signal is limited to 0.003 to 0.009 m^-1/sec by the EPS depending on speed and direction - # Limit to ~2 m/s^3 up, ~3 m/s^3 down at 75 mph - # Worst case, the low speed limits will allow 4.3 m/s^3 up, 4.9 m/s^3 down at 75 mph - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.0002, 0.0001]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.000225, 0.00015]) - CURVATURE_ERROR = 0.002 # ~6 degrees at 10 m/s, ~10 degrees at 35 m/s - - ACCEL_MAX = 2.0 # m/s^2 max acceleration - ACCEL_MIN = -3.5 # m/s^2 max deceleration - MIN_GAS = -0.5 - INACTIVE_GAS = -5.0 - - def __init__(self, CP): - pass - - -class FordFlags(IntFlag): - # Static flags - CANFD = 1 - - -class RADAR: - DELPHI_ESR = 'ford_fusion_2018_adas' - DELPHI_MRR = 'FORD_CADS' - - -class Footnote(Enum): - FOCUS = CarFootnote( - "Refers only to the Focus Mk4 (C519) available in Europe/China/Taiwan/Australasia, not the Focus Mk3 (C346) in " + - "North and South America/Southeast Asia.", - Column.MODEL, - ) - - -@dataclass -class FordCarDocs(CarDocs): - package: str = "Co-Pilot360 Assist+" - hybrid: bool = False - plug_in_hybrid: bool = False - - def init_make(self, CP: car.CarParams): - harness = CarHarness.ford_q4 if CP.flags & FordFlags.CANFD else CarHarness.ford_q3 - if CP.carFingerprint in (CAR.FORD_BRONCO_SPORT_MK1, CAR.FORD_MAVERICK_MK1, CAR.FORD_F_150_MK14, CAR.FORD_F_150_LIGHTNING_MK1): - self.car_parts = CarParts([Device.threex_angled_mount, harness]) - else: - self.car_parts = CarParts([Device.threex, harness]) - - -@dataclass -class FordPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR)) - - def init(self): - for car_docs in list(self.car_docs): - if car_docs.hybrid: - name = f"{car_docs.make} {car_docs.model} Hybrid {car_docs.years}" - self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) - if car_docs.plug_in_hybrid: - name = f"{car_docs.make} {car_docs.model} Plug-in Hybrid {car_docs.years}" - self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) - - -@dataclass -class FordCANFDPlatformConfig(FordPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', None)) - - def init(self): - super().init() - self.flags |= FordFlags.CANFD - - -class CAR(Platforms): - FORD_BRONCO_SPORT_MK1 = FordPlatformConfig( - [FordCarDocs("Ford Bronco Sport 2021-23")], - CarSpecs(mass=1625, wheelbase=2.67, steerRatio=17.7), - ) - FORD_ESCAPE_MK4 = FordPlatformConfig( - [ - FordCarDocs("Ford Escape 2020-22", hybrid=True, plug_in_hybrid=True), - FordCarDocs("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), - ], - CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), - ) - FORD_EXPLORER_MK6 = FordPlatformConfig( - [ - FordCarDocs("Ford Explorer 2020-23", hybrid=True), # Hybrid: Limited and Platinum only - FordCarDocs("Lincoln Aviator 2020-23", "Co-Pilot360 Plus", plug_in_hybrid=True), # Hybrid: Grand Touring only - ], - CarSpecs(mass=2050, wheelbase=3.025, steerRatio=16.8), - ) - FORD_F_150_MK14 = FordCANFDPlatformConfig( - [FordCarDocs("Ford F-150 2022-23", "Co-Pilot360 Active 2.0", hybrid=True)], - CarSpecs(mass=2000, wheelbase=3.69, steerRatio=17.0), - ) - FORD_F_150_LIGHTNING_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford F-150 Lightning 2021-23", "Co-Pilot360 Active 2.0")], - CarSpecs(mass=2948, wheelbase=3.70, steerRatio=16.9), - ) - FORD_FOCUS_MK4 = FordPlatformConfig( - [FordCarDocs("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS], hybrid=True)], # mHEV only - CarSpecs(mass=1350, wheelbase=2.7, steerRatio=15.0), - ) - FORD_MAVERICK_MK1 = FordPlatformConfig( - [ - FordCarDocs("Ford Maverick 2022", "LARIAT Luxury", hybrid=True), - FordCarDocs("Ford Maverick 2023-24", "Co-Pilot360 Assist", hybrid=True), - ], - CarSpecs(mass=1650, wheelbase=3.076, steerRatio=17.0), - ) - FORD_MUSTANG_MACH_E_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Mustang Mach-E 2021-23", "Co-Pilot360 Active 2.0")], - CarSpecs(mass=2200, wheelbase=2.984, steerRatio=17.0), # TODO: check steer ratio - ) - FORD_RANGER_MK2 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering")], - CarSpecs(mass=2000, wheelbase=3.27, steerRatio=17.0), - ) - - -# FW response contains a combined software and part number -# A-Z except no I, O or W -# e.g. NZ6A-14C204-AAA -# 1222-333333-444 -# 1 = Model year hint (approximates model year/generation) -# 2 = Platform hint -# 3 = Part number -# 4 = Software version -FW_ALPHABET = b'A-HJ-NP-VX-Z' -FW_PATTERN = re.compile(b'^(?P[' + FW_ALPHABET + b'])' + - b'(?P[0-9' + FW_ALPHABET + b']{3})-' + - b'(?P[0-9' + FW_ALPHABET + b']{5,6})-' + - b'(?P[' + FW_ALPHABET + b']{2,})\x00*$') - - -def get_platform_codes(fw_versions: list[bytes] | set[bytes]) -> set[tuple[bytes, bytes]]: - codes = set() - for fw in fw_versions: - match = FW_PATTERN.match(fw) - if match is not None: - codes.add((match.group('platform_hint'), match.group('model_year_hint'))) - - return codes - - -def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, vin: str, offline_fw_versions: OfflineFwVersions) -> set[str]: - candidates: set[str] = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform hint, within model year hint range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & model year hints - codes = get_platform_codes(expected_versions) - expected_platform_codes = {code for code, _ in codes} - expected_model_year_hints = {model_year_hint for _, model_year_hint in codes} - - # Found platform codes & model year hints - codes = get_platform_codes(live_fw_versions.get(addr, set())) - found_platform_codes = {code for code, _ in codes} - found_model_year_hints = {model_year_hint for _, model_year_hint in codes} - - # Check platform code matches for any found versions - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - # Check any model year hint within range in the database. Note that some models have more than one - # platform code per ECU which we don't consider as separate ranges - if not any(min(expected_model_year_hints) <= found_model_year_hint <= max(expected_model_year_hints) for - found_model_year_hint in found_model_year_hints): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return candidates - - -# All of these ECUs must be present and are expected to have platform codes we can match -PLATFORM_CODE_ECUS = (Ecu.abs, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) - -DATA_IDENTIFIER_FORD_ASBUILT = 0xDE00 - -ASBUILT_BLOCKS: list[tuple[int, list]] = [ - (1, [Ecu.debug, Ecu.fwdCamera, Ecu.eps]), - (2, [Ecu.abs, Ecu.debug, Ecu.eps]), - (3, [Ecu.abs, Ecu.debug, Ecu.eps]), - (4, [Ecu.debug, Ecu.fwdCamera]), - (5, [Ecu.debug]), - (6, [Ecu.debug]), - (7, [Ecu.debug]), - (8, [Ecu.debug]), - (9, [Ecu.debug]), - (16, [Ecu.debug, Ecu.fwdCamera]), - (18, [Ecu.fwdCamera]), - (20, [Ecu.fwdCamera]), - (21, [Ecu.fwdCamera]), -] - - -def ford_asbuilt_block_request(block_id: int): - return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) - - -def ford_asbuilt_block_response(block_id: int): - return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # CAN and CAN FD queries are combined. - # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], - logging=True, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], - bus=0, - auxiliary=True, - ), - *[Request( - [StdQueries.TESTER_PRESENT_REQUEST, ford_asbuilt_block_request(block_id)], - [StdQueries.TESTER_PRESENT_RESPONSE, ford_asbuilt_block_response(block_id)], - whitelist_ecus=ecus, - bus=0, - logging=True, - ) for block_id, ecus in ASBUILT_BLOCKS], - ], - extra_ecus=[ - (Ecu.engine, 0x7e0, None), # Powertrain Control Module - # Note: We are unlikely to get a response from behind the gateway - (Ecu.shiftByWire, 0x732, None), # Gear Shift Module - (Ecu.debug, 0x7d0, None), # Accessory Protocol Interface Module - ], - # Custom fuzzy fingerprinting function using platform and model year hints - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py deleted file mode 100755 index bb2827571cd771..00000000000000 --- a/selfdrive/car/fw_query_definitions.py +++ /dev/null @@ -1,119 +0,0 @@ -#!/usr/bin/env python3 -import capnp -import copy -from dataclasses import dataclass, field -import struct -from collections.abc import Callable - -import panda.python.uds as uds - -AddrType = tuple[int, int | None] -EcuAddrBusType = tuple[int, int | None, int] -EcuAddrSubAddr = tuple[int, int, int | None] - -LiveFwVersions = dict[AddrType, set[bytes]] -OfflineFwVersions = dict[str, dict[EcuAddrSubAddr, list[bytes]]] - -# A global list of addresses we will only ever consider for VIN responses -# engine, hybrid controller, Ford abs, Hyundai CAN FD cluster, 29-bit engine, PGM-FI -# TODO: move these to each brand's FW query config -STANDARD_VIN_ADDRS = [0x7e0, 0x7e2, 0x760, 0x7c6, 0x18da10f1, 0x18da0ef1] - - -def p16(val): - return struct.pack("!H", val) - - -class StdQueries: - # FW queries - TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT, 0x0]) - TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40, 0x0]) - - SHORT_TESTER_PRESENT_REQUEST = bytes([uds.SERVICE_TYPE.TESTER_PRESENT]) - SHORT_TESTER_PRESENT_RESPONSE = bytes([uds.SERVICE_TYPE.TESTER_PRESENT + 0x40]) - - DEFAULT_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, - uds.SESSION_TYPE.DEFAULT]) - DEFAULT_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, - uds.SESSION_TYPE.DEFAULT, 0x0, 0x32, 0x1, 0xf4]) - - EXTENDED_DIAGNOSTIC_REQUEST = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, - uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC]) - EXTENDED_DIAGNOSTIC_RESPONSE = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, - uds.SESSION_TYPE.EXTENDED_DIAGNOSTIC, 0x0, 0x32, 0x1, 0xf4]) - - MANUFACTURER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) - MANUFACTURER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) - - SUPPLIER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_VERSION_NUMBER) - SUPPLIER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_VERSION_NUMBER) - - UDS_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) - UDS_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) - - OBD_VERSION_REQUEST = b'\x09\x04' - OBD_VERSION_RESPONSE = b'\x49\x04' - - # VIN queries - OBD_VIN_REQUEST = b'\x09\x02' - OBD_VIN_RESPONSE = b'\x49\x02\x01' - - UDS_VIN_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN) - UDS_VIN_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN) - - GM_VIN_REQUEST = b'\x1a\x90' - GM_VIN_RESPONSE = b'\x5a\x90' - - KWP_VIN_REQUEST = b'\x21\x81' - KWP_VIN_RESPONSE = b'\x61\x81' - - -@dataclass -class Request: - request: list[bytes] - response: list[bytes] - whitelist_ecus: list[int] = field(default_factory=list) - rx_offset: int = 0x8 - bus: int = 1 - # Whether this query should be run on the first auxiliary panda (CAN FD cars for example) - auxiliary: bool = False - # FW responses from these queries will not be used for fingerprinting - logging: bool = False - # pandad toggles OBD multiplexing on/off as needed - obd_multiplexing: bool = True - - -@dataclass -class FwQueryConfig: - requests: list[Request] - # TODO: make this automatic and remove hardcoded lists, or do fingerprinting with ecus - # Overrides and removes from essential ecus for specific models and ecus (exact matching) - non_essential_ecus: dict[capnp.lib.capnp._EnumModule, list[str]] = field(default_factory=dict) - # Ecus added for data collection, not to be fingerprinted on - extra_ecus: list[tuple[capnp.lib.capnp._EnumModule, int, int | None]] = field(default_factory=list) - # Function a brand can implement to provide better fuzzy matching. Takes in FW versions and VIN, - # returns set of candidates. Only will match if one candidate is returned - match_fw_to_car_fuzzy: Callable[[LiveFwVersions, str, OfflineFwVersions], set[str]] | None = None - - def __post_init__(self): - for i in range(len(self.requests)): - if self.requests[i].auxiliary: - new_request = copy.deepcopy(self.requests[i]) - new_request.bus += 4 - self.requests.append(new_request) - - def get_all_ecus(self, offline_fw_versions: OfflineFwVersions, - include_extra_ecus: bool = True) -> set[EcuAddrSubAddr]: - # Add ecus in database + extra ecus - brand_ecus = {ecu for ecus in offline_fw_versions.values() for ecu in ecus} - - if include_extra_ecus: - brand_ecus |= set(self.extra_ecus) - - return brand_ecus diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py deleted file mode 100755 index 7cee14bfbdc789..00000000000000 --- a/selfdrive/car/fw_versions.py +++ /dev/null @@ -1,394 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict -from collections.abc import Callable, Iterator -from typing import Any, Protocol, TypeVar - -from tqdm import tqdm -import capnp - -import panda.python.uds as uds -from cereal import car -from openpilot.selfdrive.car import carlog -from openpilot.selfdrive.car.ecu_addrs import get_ecu_addrs -from openpilot.selfdrive.car.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.can_definitions import CanRecvCallable, CanSendCallable -from openpilot.selfdrive.car.fw_query_definitions import AddrType, EcuAddrBusType, FwQueryConfig, LiveFwVersions, OfflineFwVersions -from openpilot.selfdrive.car.interfaces import get_interface_attr -from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery - -Ecu = car.CarParams.Ecu -ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] -FUZZY_EXCLUDE_ECUS = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug] - -FW_QUERY_CONFIGS: dict[str, FwQueryConfig] = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) -VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) - -MODEL_TO_BRAND = {c: b for b, e in VERSIONS.items() for c in e} -REQUESTS = [(brand, config, r) for brand, config in FW_QUERY_CONFIGS.items() for r in config.requests] - -T = TypeVar('T') -ObdCallback = Callable[[bool], None] - - -def chunks(l: list[T], n: int = 128) -> Iterator[list[T]]: - for i in range(0, len(l), n): - yield l[i:i + n] - - -def is_brand(brand: str, filter_brand: str | None) -> bool: - """Returns if brand matches filter_brand or no brand filter is specified""" - return filter_brand is None or brand == filter_brand - - -def build_fw_dict(fw_versions: list[capnp.lib.capnp._DynamicStructBuilder], filter_brand: str = None) -> dict[AddrType, set[bytes]]: - fw_versions_dict: defaultdict[AddrType, set[bytes]] = defaultdict(set) - for fw in fw_versions: - if is_brand(fw.brand, filter_brand) and not fw.logging: - sub_addr = fw.subAddress if fw.subAddress != 0 else None - fw_versions_dict[(fw.address, sub_addr)].add(fw.fwVersion) - return dict(fw_versions_dict) - - -class MatchFwToCar(Protocol): - def __call__(self, live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True) -> set[str]: - ... - - -def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True, exclude: str = None) -> set[str]: - """Do a fuzzy FW match. This function will return a match, and the number of firmware version - that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars - the match is rejected.""" - - # Build lookup table from (addr, sub_addr, fw) to list of candidate cars - all_fw_versions = defaultdict(list) - for candidate, fw_by_addr in FW_VERSIONS.items(): - if not is_brand(MODEL_TO_BRAND[candidate], match_brand): - continue - - if candidate == exclude: - continue - - for addr, fws in fw_by_addr.items(): - # These ECUs are known to be shared between models (EPS only between hybrid/ICE version) - # Getting this exactly right isn't crucial, but excluding camera and radar makes it almost - # impossible to get 3 matching versions, even if two models with shared parts are released at the same - # time and only one is in our database. - if addr[0] in FUZZY_EXCLUDE_ECUS: - continue - for f in fws: - all_fw_versions[(addr[1], addr[2], f)].append(candidate) - - matched_ecus = set() - match: str | None = None - for addr, versions in live_fw_versions.items(): - ecu_key = (addr[0], addr[1]) - for version in versions: - # All cars that have this FW response on the specified address - candidates = all_fw_versions[(*ecu_key, version)] - - if len(candidates) == 1: - matched_ecus.add(ecu_key) - if match is None: - match = candidates[0] - # We uniquely matched two different cars. No fuzzy match possible - elif match != candidates[0]: - return set() - - # Note that it is possible to match to a candidate without all its ECUs being present - # if there are enough matches. FIXME: parameterize this or require all ECUs to exist like exact matching - if match and len(matched_ecus) >= 2: - if log: - carlog.error(f"Fingerprinted {match} using fuzzy match. {len(matched_ecus)} matching ECUs") - return {match} - else: - return set() - - -def match_fw_to_car_exact(live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True, extra_fw_versions: dict = None) -> set[str]: - """Do an exact FW match. Returns all cars that match the given - FW versions for a list of "essential" ECUs. If an ECU is not considered - essential the FW version can be missing to get a fingerprint, but if it's present it - needs to match the database.""" - if extra_fw_versions is None: - extra_fw_versions = {} - - invalid = set() - candidates = {c: f for c, f in FW_VERSIONS.items() if - is_brand(MODEL_TO_BRAND[c], match_brand)} - - for candidate, fws in candidates.items(): - config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]] - for ecu, expected_versions in fws.items(): - expected_versions = expected_versions + extra_fw_versions.get(candidate, {}).get(ecu, []) - ecu_type = ecu[0] - addr = ecu[1:] - - found_versions = live_fw_versions.get(addr, set()) - if not len(found_versions): - # Some models can sometimes miss an ecu, or show on two different addresses - # FIXME: this logic can be improved to be more specific, should require one of the two addresses - if candidate in config.non_essential_ecus.get(ecu_type, []): - continue - - # Ignore non essential ecus - if ecu_type not in ESSENTIAL_ECUS: - continue - - # Virtual debug ecu doesn't need to match the database - if ecu_type == Ecu.debug: - continue - - if not any(found_version in expected_versions for found_version in found_versions): - invalid.add(candidate) - break - - return set(candidates.keys()) - invalid - - -def match_fw_to_car(fw_versions: list[capnp.lib.capnp._DynamicStructBuilder], vin: str, - allow_exact: bool = True, allow_fuzzy: bool = True, log: bool = True) -> tuple[bool, set[str]]: - # Try exact matching first - exact_matches: list[tuple[bool, MatchFwToCar]] = [] - if allow_exact: - exact_matches = [(True, match_fw_to_car_exact)] - if allow_fuzzy: - exact_matches.append((False, match_fw_to_car_fuzzy)) - - for exact_match, match_func in exact_matches: - # For each brand, attempt to fingerprint using all FW returned from its queries - matches: set[str] = set() - for brand in VERSIONS.keys(): - fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) - matches |= match_func(fw_versions_dict, match_brand=brand, log=log) - - # If specified and no matches so far, fall back to brand's fuzzy fingerprinting function - config = FW_QUERY_CONFIGS[brand] - if not exact_match and not len(matches) and config.match_fw_to_car_fuzzy is not None: - matches |= config.match_fw_to_car_fuzzy(fw_versions_dict, vin, VERSIONS[brand]) - - if len(matches): - return exact_match, matches - - return True, set() - - -def get_present_ecus(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, num_pandas: int = 1) -> set[EcuAddrBusType]: - # queries are split by OBD multiplexing mode - queries: dict[bool, list[list[EcuAddrBusType]]] = {True: [], False: []} - parallel_queries: dict[bool, list[EcuAddrBusType]] = {True: [], False: []} - responses: set[EcuAddrBusType] = set() - - for brand, config, r in REQUESTS: - # Skip query if no panda available - if r.bus > num_pandas * 4 - 1: - continue - - for ecu_type, addr, sub_addr in config.get_all_ecus(VERSIONS[brand]): - # Only query ecus in whitelist if whitelist is not empty - if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: - a = (addr, sub_addr, r.bus) - # Build set of queries - if sub_addr is None: - if a not in parallel_queries[r.obd_multiplexing]: - parallel_queries[r.obd_multiplexing].append(a) - else: # subaddresses must be queried one by one - if [a] not in queries[r.obd_multiplexing]: - queries[r.obd_multiplexing].append([a]) - - # Build set of expected responses to filter - response_addr = uds.get_rx_addr_for_tx_addr(addr, r.rx_offset) - responses.add((response_addr, sub_addr, r.bus)) - - for obd_multiplexing in queries: - queries[obd_multiplexing].insert(0, parallel_queries[obd_multiplexing]) - - ecu_responses = set() - for obd_multiplexing in queries: - set_obd_multiplexing(obd_multiplexing) - for query in queries[obd_multiplexing]: - ecu_responses.update(get_ecu_addrs(can_recv, can_send, set(query), responses, timeout=0.1)) - return ecu_responses - - -def get_brand_ecu_matches(ecu_rx_addrs: set[EcuAddrBusType]) -> dict[str, set[AddrType]]: - """Returns dictionary of brands and matches with ECUs in their FW versions""" - - brand_addrs = {brand: {(addr, subaddr) for _, addr, subaddr in config.get_all_ecus(VERSIONS[brand])} for - brand, config in FW_QUERY_CONFIGS.items()} - brand_matches: dict[str, set[AddrType]] = {brand: set() for brand, _, _ in REQUESTS} - - brand_rx_offsets = {(brand, r.rx_offset) for brand, _, r in REQUESTS} - for addr, sub_addr, _ in ecu_rx_addrs: - # Since we can't know what request an ecu responded to, add matches for all possible rx offsets - for brand, rx_offset in brand_rx_offsets: - a = (uds.get_rx_addr_for_tx_addr(addr, -rx_offset), sub_addr) - if a in brand_addrs[brand]: - brand_matches[brand].add(a) - - return brand_matches - - -def get_fw_versions_ordered(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, vin: str, - ecu_rx_addrs: set[EcuAddrBusType], timeout: float = 0.1, num_pandas: int = 1, debug: bool = False, - progress: bool = False) -> list[capnp.lib.capnp._DynamicStructBuilder]: - """Queries for FW versions ordering brands by likelihood, breaks when exact match is found""" - - all_car_fw = [] - brand_matches = get_brand_ecu_matches(ecu_rx_addrs) - - for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True): - # Skip this brand if there are no matching present ECUs - if not len(brand_matches[brand]): - continue - - car_fw = get_fw_versions(can_recv, can_send, set_obd_multiplexing, query_brand=brand, timeout=timeout, num_pandas=num_pandas, debug=debug, - progress=progress) - all_car_fw.extend(car_fw) - - # If there is a match using this brand's FW alone, finish querying early - _, matches = match_fw_to_car(car_fw, vin, log=False) - if len(matches) == 1: - break - - return all_car_fw - - -def get_fw_versions(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, query_brand: str = None, - extra: OfflineFwVersions = None, timeout: float = 0.1, num_pandas: int = 1, debug: bool = False, - progress: bool = False) -> list[capnp.lib.capnp._DynamicStructBuilder]: - versions = VERSIONS.copy() - - if query_brand is not None: - versions = {query_brand: versions[query_brand]} - - if extra is not None: - versions.update(extra) - - # Extract ECU addresses to query from fingerprints - # ECUs using a subaddress need be queried one by one, the rest can be done in parallel - addrs = [] - parallel_addrs = [] - ecu_types = {} - - for brand, brand_versions in versions.items(): - config = FW_QUERY_CONFIGS[brand] - for ecu_type, addr, sub_addr in config.get_all_ecus(brand_versions): - a = (brand, addr, sub_addr) - if a not in ecu_types: - ecu_types[a] = ecu_type - - if sub_addr is None: - if a not in parallel_addrs: - parallel_addrs.append(a) - else: - if [a] not in addrs: - addrs.append([a]) - - addrs.insert(0, parallel_addrs) - - # Get versions and build capnp list to put into CarParams - car_fw = [] - requests = [(brand, config, r) for brand, config, r in REQUESTS if is_brand(brand, query_brand)] - for addr_group in tqdm(addrs, disable=not progress): # split by subaddr, if any - for addr_chunk in chunks(addr_group): - for brand, config, r in requests: - # Skip query if no panda available - if r.bus > num_pandas * 4 - 1: - continue - - # Toggle OBD multiplexing for each request - if r.bus % 4 == 1: - set_obd_multiplexing(r.obd_multiplexing) - - try: - query_addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and - (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] - - if query_addrs: - query = IsoTpParallelQuery(can_send, can_recv, r.bus, query_addrs, r.request, r.response, r.rx_offset, debug=debug) - for (tx_addr, sub_addr), version in query.get_data(timeout).items(): - f = car.CarParams.CarFw.new_message() - - f.ecu = ecu_types.get((brand, tx_addr, sub_addr), Ecu.unknown) - f.fwVersion = version - f.address = tx_addr - f.responseAddress = uds.get_rx_addr_for_tx_addr(tx_addr, r.rx_offset) - f.request = r.request - f.brand = brand - f.bus = r.bus - f.logging = r.logging or (f.ecu, tx_addr, sub_addr) in config.extra_ecus - f.obdMultiplexing = r.obd_multiplexing - - if sub_addr is not None: - f.subAddress = sub_addr - - car_fw.append(f) - except Exception: - carlog.exception("FW query exception") - - return car_fw - - -if __name__ == "__main__": - import time - import argparse - import cereal.messaging as messaging - from openpilot.common.params import Params - from openpilot.selfdrive.car.vin import get_vin - from openpilot.selfdrive.car.card import obd_callback - - parser = argparse.ArgumentParser(description='Get firmware version of ECUs') - parser.add_argument('--scan', action='store_true') - parser.add_argument('--debug', action='store_true') - parser.add_argument('--brand', help='Only query addresses/with requests for this brand') - args = parser.parse_args() - - logcan = messaging.sub_sock('can') - pandaStates_sock = messaging.sub_sock('pandaStates') - sendcan = messaging.pub_sock('sendcan') - - # Set up params for pandad - params = Params() - params.remove("FirmwareQueryDone") - params.put_bool("IsOnroad", False) - time.sleep(0.2) # thread is 10 Hz - params.put_bool("IsOnroad", True) - set_obd_multiplexing = obd_callback(params) - - extra: Any = None - if args.scan: - extra = {} - # Honda - for i in range(256): - extra[(Ecu.unknown, 0x18da00f1 + (i << 8), None)] = [] - extra[(Ecu.unknown, 0x700 + i, None)] = [] - extra[(Ecu.unknown, 0x750, i)] = [] - extra = {"any": {"debug": extra}} - - num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates) - - t = time.time() - print("Getting vin...") - set_obd_multiplexing(True) - vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (0, 1), debug=args.debug) - print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') - print(f"Getting VIN took {time.time() - t:.3f} s") - print() - - t = time.time() - fw_vers = get_fw_versions(logcan, sendcan, set_obd_multiplexing, query_brand=args.brand, extra=extra, num_pandas=num_pandas, debug=args.debug, progress=True) - _, candidates = match_fw_to_car(fw_vers, vin) - - print() - print("Found FW versions") - print("{") - padding = max([len(fw.brand) for fw in fw_vers] or [0]) - for version in fw_vers: - subaddr = None if version.subAddress == 0 else hex(version.subAddress) - print(f" Brand: {version.brand:{padding}}, bus: {version.bus}, OBD: {version.obdMultiplexing} - " + - f"(Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") - print("}") - - print() - print("Possible matches:", candidates) - print(f"Getting fw took {time.time() - t:.3f} s") diff --git a/selfdrive/car/gm/__init__.py b/selfdrive/car/gm/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py deleted file mode 100644 index dff280ed9a735d..00000000000000 --- a/selfdrive/car/gm/carcontroller.py +++ /dev/null @@ -1,163 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import DT_CTRL, apply_driver_steer_torque_limits -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.gm import gmcan -from openpilot.selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons -from openpilot.selfdrive.car.helpers import interp -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -NetworkLocation = car.CarParams.NetworkLocation -LongCtrlState = car.CarControl.Actuators.LongControlState - -# Camera cancels up to 0.1s after brake is pressed, ECM allows 0.5s -CAMERA_CANCEL_DELAY_FRAMES = 10 -# Enforce a minimum interval between steering messages to avoid a fault -MIN_STEER_MSG_INTERVAL_MS = 15 - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.start_time = 0. - self.apply_steer_last = 0 - self.apply_gas = 0 - self.apply_brake = 0 - self.last_steer_frame = 0 - self.last_button_frame = 0 - self.cancel_counter = 0 - - self.lka_steering_cmd_counter = 0 - self.lka_icon_status_last = (False, False) - - self.params = CarControllerParams(self.CP) - - self.packer_pt = CANPacker(DBC[self.CP.carFingerprint]['pt']) - self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar']) - self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis']) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - hud_alert = hud_control.visualAlert - hud_v_cruise = hud_control.setSpeed - if hud_v_cruise > 70: - hud_v_cruise = 0 - - # Send CAN commands. - can_sends = [] - - # Steering (Active: 50Hz, inactive: 10Hz) - steer_step = self.params.STEER_STEP if CC.latActive else self.params.INACTIVE_STEER_STEP - - if self.CP.networkLocation == NetworkLocation.fwdCamera: - # Also send at 50Hz: - # - on startup, first few msgs are blocked - # - until we're in sync with camera so counters align when relay closes, preventing a fault. - # openpilot can subtly drift, so this is activated throughout a drive to stay synced - out_of_sync = self.lka_steering_cmd_counter % 4 != (CS.cam_lka_steering_cmd_counter + 1) % 4 - if CS.loopback_lka_steering_cmd_ts_nanos == 0 or out_of_sync: - steer_step = self.params.STEER_STEP - - self.lka_steering_cmd_counter += 1 if CS.loopback_lka_steering_cmd_updated else 0 - - # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we - # received the ASCMLKASteeringCmd loopback confirmation too recently - last_lka_steer_msg_ms = (now_nanos - CS.loopback_lka_steering_cmd_ts_nanos) * 1e-6 - if (self.frame - self.last_steer_frame) >= steer_step and last_lka_steer_msg_ms > MIN_STEER_MSG_INTERVAL_MS: - # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus - if CS.loopback_lka_steering_cmd_ts_nanos == 0: - self.lka_steering_cmd_counter = CS.pt_lka_steering_cmd_counter + 1 - - if CC.latActive: - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) - else: - apply_steer = 0 - - self.last_steer_frame = self.frame - self.apply_steer_last = apply_steer - idx = self.lka_steering_cmd_counter % 4 - can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) - - if self.CP.openpilotLongitudinalControl: - # Gas/regen, brakes, and UI commands - all at 25Hz - if self.frame % 4 == 0: - stopping = actuators.longControlState == LongCtrlState.stopping - if not CC.longActive: - # ASCM sends max regen when not enabled - self.apply_gas = self.params.INACTIVE_REGEN - self.apply_brake = 0 - else: - self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) - self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) - # Don't allow any gas above inactive regen while stopping - # FIXME: brakes aren't applied immediately when enabling at a stop - if stopping: - self.apply_gas = self.params.INACTIVE_REGEN - - idx = (self.frame // 4) % 4 - - at_full_stop = CC.longActive and CS.out.standstill - near_stop = CC.longActive and (CS.out.vEgo < self.params.NEAR_STOP_BRAKE_PHASE) - friction_brake_bus = CanBus.CHASSIS - # GM Camera exceptions - # TODO: can we always check the longControlState? - if self.CP.networkLocation == NetworkLocation.fwdCamera: - at_full_stop = at_full_stop and stopping - friction_brake_bus = CanBus.POWERTRAIN - - # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation - can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) - can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, friction_brake_bus, self.apply_brake, - idx, CC.enabled, near_stop, at_full_stop, self.CP)) - - # Send dashboard UI commands (ACC status) - send_fcw = hud_alert == VisualAlert.fcw - can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, - hud_v_cruise * CV.MS_TO_KPH, hud_control, send_fcw)) - - # Radar needs to know current speed and yaw rate (50hz), - # and that ADAS is alive (10hz) - if not self.CP.radarUnavailable: - tt = self.frame * DT_CTRL - time_and_headlights_step = 10 - if self.frame % time_and_headlights_step == 0: - idx = (self.frame // time_and_headlights_step) % 4 - can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) - can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) - - speed_and_accelerometer_step = 2 - if self.frame % speed_and_accelerometer_step == 0: - idx = (self.frame // speed_and_accelerometer_step) % 4 - can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) - can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, CS.out.vEgo, idx)) - - if self.CP.networkLocation == NetworkLocation.gateway and self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: - can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) - - else: - # While car is braking, cancel button causes ECM to enter a soft disable state with a fault status. - # A delayed cancellation allows camera to cancel and avoids a fault when user depresses brake quickly - self.cancel_counter = self.cancel_counter + 1 if CC.cruiseControl.cancel else 0 - - # Stock longitudinal, integrated at camera - if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: - if self.cancel_counter > CAMERA_CANCEL_DELAY_FRAMES: - self.last_button_frame = self.frame - can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) - - if self.CP.networkLocation == NetworkLocation.fwdCamera: - # Silence "Take Steering" alert sent by camera, forward PSCMStatus with HandsOffSWlDetectionStatus=1 - if self.frame % 10 == 0: - can_sends.append(gmcan.create_pscm_status(self.packer_pt, CanBus.CAMERA, CS.pscm_status)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - new_actuators.gas = self.apply_gas - new_actuators.brake = self.apply_brake - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py deleted file mode 100644 index 97dbd389f4f6b2..00000000000000 --- a/selfdrive/car/gm/carstate.py +++ /dev/null @@ -1,180 +0,0 @@ -import copy -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.helpers import mean -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.gm.values import DBC, AccState, CanBus, STEER_THRESHOLD - -TransmissionType = car.CarParams.TransmissionType -NetworkLocation = car.CarParams.NetworkLocation -STANDSTILL_THRESHOLD = 10 * 0.0311 * CV.KPH_TO_MS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] - self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. - self.cluster_min_speed = CV.KPH_TO_MS / 2. - - self.loopback_lka_steering_cmd_updated = False - self.loopback_lka_steering_cmd_ts_nanos = 0 - self.pt_lka_steering_cmd_counter = 0 - self.cam_lka_steering_cmd_counter = 0 - self.buttons_counter = 0 - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, pt_cp, cam_cp, loopback_cp): - ret = car.CarState.new_message() - - self.prev_cruise_buttons = self.cruise_buttons - self.prev_distance_button = self.distance_button - self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] - self.distance_button = pt_cp.vl["ASCMSteeringButton"]["DistanceButton"] - self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] - self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) - # This is to avoid a fault where you engage while still moving backwards after shifting to D. - # An Equinox has been seen with an unsupported status (3), so only check if either wheel is in reverse (2) - self.moving_backward = (pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2) or (pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2) - - # Variables used for avoiding LKAS faults - self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 - if self.loopback_lka_steering_cmd_updated: - self.loopback_lka_steering_cmd_ts_nanos = loopback_cp.ts_nanos["ASCMLKASteeringCmd"]["RollingCounter"] - if self.CP.networkLocation == NetworkLocation.fwdCamera: - self.pt_lka_steering_cmd_counter = pt_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] - self.cam_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] - - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], - pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"], - pt_cp.vl["EBCMWheelSpdRear"]["RLWheelSpd"], - pt_cp.vl["EBCMWheelSpdRear"]["RRWheelSpd"], - ) - ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - # sample rear wheel speeds, standstill=True if ECM allows engagement with brake - ret.standstill = ret.wheelSpeeds.rl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - if pt_cp.vl["ECMPRDNL2"]["ManualMode"] == 1: - ret.gearShifter = self.parse_gear_shifter("T") - else: - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL2"]["PRNDL2"], None)) - - ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] - if self.CP.networkLocation == NetworkLocation.fwdCamera: - ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["BrakePressed"] != 0 - else: - # Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe - # that the brake is being intermittently pressed without user interaction. - # To avoid a cruise fault we need to use a conservative brake position threshold - # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf - ret.brakePressed = ret.brake >= 8 - - # Regen braking is braking - if self.CP.transmissionType == TransmissionType.direct: - ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 - - ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. - ret.gasPressed = ret.gas > 1e-5 - - ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"] - ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelRate"] - ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"] - ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # 0 inactive, 1 active, 2 temporarily limited, 3 failed - self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"] - ret.steerFaultTemporary = self.lkas_status == 2 - ret.steerFaultPermanent = self.lkas_status == 3 - - # 1 - open, 0 - closed - ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]["FrontLeftDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["FrontRightDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["RearLeftDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["RearRightDoor"] == 1) - - # 1 - latched - ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]["LeftSeatBelt"] == 0 - ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1 - ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 - - ret.parkingBrake = pt_cp.vl["BCMGeneralPlatformStatus"]["ParkBrakeSwActive"] == 1 - ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 - ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 - ret.accFaulted = (pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED or - pt_cp.vl["EBCMFrictionBrakeStatus"]["FrictionBrakeUnavailable"] == 1) - - ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF - ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL - if self.CP.networkLocation == NetworkLocation.fwdCamera: - ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS - ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 - # openpilot controls nonAdaptive when not pcmCruise - if self.CP.pcmCruise: - ret.cruiseState.nonAdaptive = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCCruiseState"] not in (2, 3) - - if self.CP.enableBsm: - ret.leftBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["LeftBSM"] == 1 - ret.rightBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["RightBSM"] == 1 - - return ret - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - ("AEBCmd", 10), - ("ASCMLKASteeringCmd", 10), - ("ASCMActiveCruiseControlStatus", 25), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.CAMERA) - - @staticmethod - def get_can_parser(CP): - messages = [ - ("BCMTurnSignals", 1), - ("ECMPRDNL2", 10), - ("PSCMStatus", 10), - ("ESPStatus", 10), - ("BCMDoorBeltStatus", 10), - ("BCMGeneralPlatformStatus", 10), - ("EBCMWheelSpdFront", 20), - ("EBCMWheelSpdRear", 20), - ("EBCMFrictionBrakeStatus", 20), - ("AcceleratorPedal2", 33), - ("ASCMSteeringButton", 33), - ("ECMEngineStatus", 100), - ("PSCMSteeringAngle", 100), - ("ECMAcceleratorPos", 80), - ] - - if CP.enableBsm: - messages.append(("BCMBlindSpotMonitor", 10)) - - # Used to read back last counter sent to PT by camera - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - ("ASCMLKASteeringCmd", 0), - ] - - if CP.transmissionType == TransmissionType.direct: - messages.append(("EBCMRegenPaddle", 50)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.POWERTRAIN) - - @staticmethod - def get_loopback_can_parser(CP): - messages = [ - ("ASCMLKASteeringCmd", 0), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.LOOPBACK) diff --git a/selfdrive/car/gm/fingerprints.py b/selfdrive/car/gm/fingerprints.py deleted file mode 100644 index 3752fbb8d32029..00000000000000 --- a/selfdrive/car/gm/fingerprints.py +++ /dev/null @@ -1,63 +0,0 @@ -# ruff: noqa: E501 -from openpilot.selfdrive.car.gm.values import CAR - -# Trailblazer also matches as a SILVERADO, TODO: split with fw versions -# FIXME: There are Equinox users with different message lengths, specifically 304 and 320 - - -FINGERPRINTS = { - CAR.HOLDEN_ASTRA: [{ - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7 - }], - CAR.CHEVROLET_VOLT: [{ - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 - }, - { - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 - }, - { - 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 - }], - CAR.BUICK_LACROSSE: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.BUICK_REGAL: [{ - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 - }], - CAR.CADILLAC_ATS: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.CHEVROLET_MALIBU: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.GMC_ACADIA: [{ - 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 - }, - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.CADILLAC_ESCALADE: [{ - 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.CADILLAC_ESCALADE_ESV: [{ - 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 - }], - CAR.CADILLAC_ESCALADE_ESV_2019: [{ - 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 - }], - CAR.CHEVROLET_BOLT_EUV: [{ - 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.CHEVROLET_SILVERADO: [{ - 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.CHEVROLET_EQUINOX: [{ - 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }, - { - 190: 6, 201: 8, 211: 2, 717: 5, 241: 6, 451: 8, 298: 8, 452: 8, 453: 6, 479: 3, 485: 8, 249: 8, 500: 6, 587: 8, 1611: 8, 289: 8, 481: 7, 193: 8, 197: 8, 209: 7, 455: 7, 489: 8, 309: 8, 413: 8, 501: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 311: 8, 510: 8, 528: 5, 532: 6, 715: 8, 560: 8, 562: 8, 707: 8, 789: 5, 869: 4, 880: 6, 761: 7, 840: 5, 842: 5, 844: 8, 313: 8, 381: 8, 386: 8, 810: 8, 322: 7, 384: 4, 800: 6, 1033: 7, 1034: 7, 1296: 4, 753: 5, 388: 8, 288: 5, 497: 8, 463: 3, 304: 3, 977: 8, 1001: 8, 1280: 4, 320: 4, 352: 5, 563: 5, 565: 5, 1221: 5, 1011: 6, 1017: 8, 1020: 8, 1249: 8, 1300: 8, 328: 1, 1217: 8, 1233: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1930: 7, 1271: 8 - }], -} - -FW_VERSIONS: dict[str, dict[tuple, list[bytes]]] = { -} diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py deleted file mode 100644 index 0b7ada3151aa21..00000000000000 --- a/selfdrive/car/gm/gmcan.py +++ /dev/null @@ -1,173 +0,0 @@ -from openpilot.selfdrive.car.can_definitions import CanData -from openpilot.selfdrive.car.gm.values import CAR - - -def create_buttons(packer, bus, idx, button): - values = { - "ACCButtons": button, - "RollingCounter": idx, - "ACCAlwaysOne": 1, - "DistanceButton": 0, - } - - checksum = 240 + int(values["ACCAlwaysOne"] * 0xf) - checksum += values["RollingCounter"] * (0x4ef if values["ACCAlwaysOne"] != 0 else 0x3f0) - checksum -= int(values["ACCButtons"] - 1) << 4 # not correct if value is 0 - checksum -= 2 * values["DistanceButton"] - - values["SteeringButtonChecksum"] = checksum - return packer.make_can_msg("ASCMSteeringButton", bus, values) - - -def create_pscm_status(packer, bus, pscm_status): - values = {s: pscm_status[s] for s in [ - "HandsOffSWDetectionMode", - "HandsOffSWlDetectionStatus", - "LKATorqueDeliveredStatus", - "LKADriverAppldTrq", - "LKATorqueDelivered", - "LKATotalTorqueDelivered", - "RollingCounter", - "PSCMStatusChecksum", - ]} - checksum_mod = int(1 - values["HandsOffSWlDetectionStatus"]) << 5 - values["HandsOffSWlDetectionStatus"] = 1 - values["PSCMStatusChecksum"] += checksum_mod - return packer.make_can_msg("PSCMStatus", bus, values) - - -def create_steering_control(packer, bus, apply_steer, idx, lkas_active): - values = { - "LKASteeringCmdActive": lkas_active, - "LKASteeringCmd": apply_steer, - "RollingCounter": idx, - "LKASteeringCmdChecksum": 0x1000 - (lkas_active << 11) - (apply_steer & 0x7ff) - idx - } - - return packer.make_can_msg("ASCMLKASteeringCmd", bus, values) - - -def create_adas_keepalive(bus): - dat = b"\x00\x00\x00\x00\x00\x00\x00" - return [CanData(0x409, dat, bus), CanData(0x40a, dat, bus)] - - -def create_gas_regen_command(packer, bus, throttle, idx, enabled, at_full_stop): - values = { - "GasRegenCmdActive": enabled, - "RollingCounter": idx, - "GasRegenCmdActiveInv": 1 - enabled, - "GasRegenCmd": throttle, - "GasRegenFullStopActive": at_full_stop, - "GasRegenAlwaysOne": 1, - "GasRegenAlwaysOne2": 1, - "GasRegenAlwaysOne3": 1, - } - - dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[1] - values["GasRegenChecksum"] = (((0xff - dat[1]) & 0xff) << 16) | \ - (((0xff - dat[2]) & 0xff) << 8) | \ - ((0x100 - dat[3] - idx) & 0xff) - - return packer.make_can_msg("ASCMGasRegenCmd", bus, values) - - -def create_friction_brake_command(packer, bus, apply_brake, idx, enabled, near_stop, at_full_stop, CP): - mode = 0x1 - - # TODO: Understand this better. Volts and ICE Camera ACC cars are 0x1 when enabled with no brake - if enabled and CP.carFingerprint in (CAR.CHEVROLET_BOLT_EUV,): - mode = 0x9 - - if apply_brake > 0: - mode = 0xa - if at_full_stop: - mode = 0xd - - # TODO: this is to have GM bringing the car to complete stop, - # but currently it conflicts with OP controls, so turned off. Not set by all cars - #elif near_stop: - # mode = 0xb - - brake = (0x1000 - apply_brake) & 0xfff - checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff - - values = { - "RollingCounter": idx, - "FrictionBrakeMode": mode, - "FrictionBrakeChecksum": checksum, - "FrictionBrakeCmd": -apply_brake - } - - return packer.make_can_msg("EBCMFrictionBrakeCmd", bus, values) - - -def create_acc_dashboard_command(packer, bus, enabled, target_speed_kph, hud_control, fcw): - target_speed = min(target_speed_kph, 255) - - values = { - "ACCAlwaysOne": 1, - "ACCResumeButton": 0, - "ACCSpeedSetpoint": target_speed, - "ACCGapLevel": hud_control.leadDistanceBars * enabled, # 3 "far", 0 "inactive" - "ACCCmdActive": enabled, - "ACCAlwaysOne2": 1, - "ACCLeadCar": hud_control.leadVisible, - "FCWAlert": 0x3 if fcw else 0 - } - - return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) - - -def create_adas_time_status(bus, tt, idx): - dat = [(tt >> 20) & 0xff, (tt >> 12) & 0xff, (tt >> 4) & 0xff, - ((tt & 0xf) << 4) + (idx << 2)] - chksum = 0x1000 - dat[0] - dat[1] - dat[2] - dat[3] - chksum = chksum & 0xfff - dat += [0x40 + (chksum >> 8), chksum & 0xff, 0x12] - return CanData(0xa1, bytes(dat), bus) - - -def create_adas_steering_status(bus, idx): - dat = [idx << 6, 0xf0, 0x20, 0, 0, 0] - chksum = 0x60 + sum(dat) - dat += [chksum >> 8, chksum & 0xff] - return CanData(0x306, bytes(dat), bus) - - -def create_adas_accelerometer_speed_status(bus, speed_ms, idx): - spd = int(speed_ms * 16) & 0xfff - accel = 0 & 0xfff - # 0 if in park/neutral, 0x10 if in reverse, 0x08 for D/L - #stick = 0x08 - near_range_cutoff = 0x27 - near_range_mode = 1 if spd <= near_range_cutoff else 0 - far_range_mode = 1 - near_range_mode - dat = [0x08, spd >> 4, ((spd & 0xf) << 4) | (accel >> 8), accel & 0xff, 0] - chksum = 0x62 + far_range_mode + (idx << 2) + dat[0] + dat[1] + dat[2] + dat[3] + dat[4] - dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] - return CanData(0x308, bytes(dat), bus) - - -def create_adas_headlights_status(packer, bus): - values = { - "Always42": 0x42, - "Always4": 0x4, - } - return packer.make_can_msg("ASCMHeadlight", bus, values) - - -def create_lka_icon_command(bus, active, critical, steer): - if active and steer == 1: - if critical: - dat = b"\x50\xc0\x14" - else: - dat = b"\x50\x40\x18" - elif active: - if critical: - dat = b"\x40\xc0\x14" - else: - dat = b"\x40\x40\x18" - else: - dat = b"\x00\x00\x00" - return CanData(0x104c006c, dat, bus) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py deleted file mode 100755 index 31b874502baa69..00000000000000 --- a/selfdrive/car/gm/interface.py +++ /dev/null @@ -1,237 +0,0 @@ -#!/usr/bin/env python3 -import os -from cereal import car -from math import fabs, exp -from panda import Panda - -from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car import create_button_events, get_safety_config, get_friction -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG -from openpilot.selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus -from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -GearShifter = car.CarState.GearShifter -TransmissionType = car.CarParams.TransmissionType -NetworkLocation = car.CarParams.NetworkLocation -BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, - CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} - - -NON_LINEAR_TORQUE_PARAMS = { - CAR.CHEVROLET_BOLT_EUV: [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178], - CAR.GMC_ACADIA: [4.78003305, 1.0, 0.3122, 0.05591772], - CAR.CHEVROLET_SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] -} - -NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_weights.json') - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX - - # Determined by iteratively plotting and minimizing error for f(angle, speed) = steer. - @staticmethod - def get_steer_feedforward_volt(desired_angle, v_ego): - desired_angle *= 0.02904609 - sigmoid = desired_angle / (1 + fabs(desired_angle)) - return 0.10006696 * sigmoid * (v_ego + 3.12485927) - - def get_steer_feedforward_function(self): - if self.CP.carFingerprint == CAR.CHEVROLET_VOLT: - return self.get_steer_feedforward_volt - else: - return CarInterfaceBase.get_steer_feedforward_default - - def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, - lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - - def sig(val): - # https://timvieira.github.io/blog/post/2014/02/11/exp-normalize-trick - if val >= 0: - return 1 / (1 + exp(-val)) - 0.5 - else: - z = exp(val) - return z / (1 + z) - 0.5 - - # The "lat_accel vs torque" relationship is assumed to be the sum of "sigmoid + linear" curves - # An important thing to consider is that the slope at 0 should be > 0 (ideally >1) - # This has big effect on the stability about 0 (noise when going straight) - # ToDo: To generalize to other GMs, explore tanh function as the nonlinear - non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) - assert non_linear_torque_params, "The params are not defined" - a, b, c, _ = non_linear_torque_params - steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) - return float(steer_torque) + friction - - def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, - lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - inputs = list(latcontrol_inputs) - if gravity_adjusted: - inputs[0] += inputs[1] - return float(self.neural_ff_model.predict(inputs)) + friction - - def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - if self.CP.carFingerprint == CAR.CHEVROLET_BOLT_EUV: - self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) - return self.torque_from_lateral_accel_neural - elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: - return self.torque_from_lateral_accel_siglin - else: - return self.torque_from_lateral_accel_linear - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "gm" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] - ret.autoResumeSng = False - ret.enableBsm = 0x142 in fingerprint[CanBus.POWERTRAIN] - - if candidate in EV_CAR: - ret.transmissionType = TransmissionType.direct - else: - ret.transmissionType = TransmissionType.automatic - - ret.longitudinalTuning.kiBP = [5., 35.] - - if candidate in CAMERA_ACC_CAR: - ret.experimentalLongitudinalAvailable = True - ret.networkLocation = NetworkLocation.fwdCamera - ret.radarUnavailable = True # no radar - ret.pcmCruise = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM - ret.minEnableSpeed = 5 * CV.KPH_TO_MS - ret.minSteerSpeed = 10 * CV.KPH_TO_MS - - # Tuning for experimental long - ret.longitudinalTuning.kiV = [2.0, 1.5] - ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling - ret.vEgoStopping = 0.25 - ret.vEgoStarting = 0.25 - - if experimental_long: - ret.pcmCruise = False - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG - - else: # ASCM, OBD-II harness - ret.openpilotLongitudinalControl = True - ret.networkLocation = NetworkLocation.gateway - ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs - ret.pcmCruise = False # stock non-adaptive cruise control is kept off - # supports stop and go, but initial engage must (conservatively) be above 18mph - ret.minEnableSpeed = 18 * CV.MPH_TO_MS - ret.minSteerSpeed = 7 * CV.MPH_TO_MS - - # Tuning - ret.longitudinalTuning.kiV = [2.4, 1.5] - - # These cars have been put into dashcam only due to both a lack of users and test coverage. - # These cars likely still work fine. Once a user confirms each car works and a test route is - # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.CHEVROLET_MALIBU, CAR.BUICK_REGAL} or \ - (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable) - - # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] - ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 - ret.steerActuatorDelay = 0.1 # Default delay, not measured yet - - ret.steerLimitTimer = 0.4 - ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz - ret.longitudinalActuatorDelay = 0.5 # large delay to initially start braking - - if candidate == CAR.CHEVROLET_VOLT: - ret.lateralTuning.pid.kpBP = [0., 40.] - ret.lateralTuning.pid.kpV = [0., 0.17] - ret.lateralTuning.pid.kiBP = [0.] - ret.lateralTuning.pid.kiV = [0.] - ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() - ret.steerActuatorDelay = 0.2 - - elif candidate == CAR.GMC_ACADIA: - ret.minEnableSpeed = -1. # engage speed is decided by pcm - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.BUICK_LACROSSE: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CADILLAC_ESCALADE: - ret.minEnableSpeed = -1. # engage speed is decided by pcm - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate in (CAR.CADILLAC_ESCALADE_ESV, CAR.CADILLAC_ESCALADE_ESV_2019): - ret.minEnableSpeed = -1. # engage speed is decided by pcm - - if candidate == CAR.CADILLAC_ESCALADE_ESV: - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] - ret.lateralTuning.pid.kf = 0.000045 - else: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_BOLT_EUV: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_SILVERADO: - # On the Bolt, the ECM and camera independently check that you are either above 5 kph or at a stop - # with foot on brake to allow engagement, but this platform only has that check in the camera. - # TODO: check if this is split by EV/ICE with more platforms in the future - if ret.openpilotLongitudinalControl: - ret.minEnableSpeed = -1. - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_EQUINOX: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_TRAILBLAZER: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_loopback) - - # Don't add event if transitioning from INIT, unless it's to an actual button - if self.CS.cruise_buttons != CruiseButtons.UNPRESS or self.CS.prev_cruise_buttons != CruiseButtons.INIT: - ret.buttonEvents = [ - *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, - unpressed_btn=CruiseButtons.UNPRESS), - *create_button_events(self.CS.distance_button, self.CS.prev_distance_button, - {1: ButtonType.gapAdjustCruise}) - ] - - # The ECM allows enabling on falling edge of set, but only rising edge of resume - events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low, - GearShifter.eco, GearShifter.manumatic], - pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) - if not self.CP.pcmCruise: - if any(b.type == ButtonType.accelCruise and b.pressed for b in ret.buttonEvents): - events.add(EventName.buttonEnable) - - # Enabling at a standstill with brake is allowed - # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs - below_min_enable_speed = ret.vEgo < self.CP.minEnableSpeed or self.CS.moving_backward - if below_min_enable_speed and not (ret.standstill and ret.brake >= 20 and - self.CP.networkLocation == NetworkLocation.fwdCamera): - events.add(EventName.belowEngageSpeed) - if ret.cruiseState.standstill: - events.add(EventName.resumeRequired) - if ret.vEgo < self.CP.minSteerSpeed: - events.add(EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py deleted file mode 100755 index b305d418b8a649..00000000000000 --- a/selfdrive/car/gm/radar_interface.py +++ /dev/null @@ -1,101 +0,0 @@ -#!/usr/bin/env python3 -import math -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.gm.values import DBC, CanBus -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -RADAR_HEADER_MSG = 1120 -SLOT_1_MSG = RADAR_HEADER_MSG + 1 -NUM_SLOTS = 20 - -# Actually it's 0x47f, but can parser only reports -# messages that are present in DBC -LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS - - -def create_radar_can_parser(car_fingerprint): - # C1A-ARS3-A by Continental - radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) - signals = list(zip(['FLRRNumValidTargets', - 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', - 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', - 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + - ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + - ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + - ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [RADAR_HEADER_MSG] * 7 + radar_targets * 6, strict=True)) - - messages = list({(s[1], 14) for s in signals}) - - return CANParser(DBC[car_fingerprint]['radar'], messages, CanBus.OBSTACLE) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - self.rcp = None if CP.radarUnavailable else create_radar_can_parser(CP.carFingerprint) - - self.trigger_msg = LAST_RADAR_MSG - self.updated_messages = set() - self.radar_ts = CP.radarTimeStep - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - header = self.rcp.vl[RADAR_HEADER_MSG] - fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ - header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ - header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - if fault: - errors.append("fault") - ret.errors = errors - - currentTargets = set() - num_targets = header['FLRRNumValidTargets'] - - # Not all radar messages describe targets, - # no need to monitor all of the self.rcp.msgs_upd - for ii in self.updated_messages: - if ii == RADAR_HEADER_MSG: - continue - - if num_targets == 0: - break - - cpt = self.rcp.vl[ii] - # Zero distance means it's an empty target slot - if cpt['TrkRange'] > 0.0: - targetId = cpt['TrkObjectID'] - currentTargets.add(targetId) - if targetId not in self.pts: - self.pts[targetId] = car.RadarData.RadarPoint.new_message() - self.pts[targetId].trackId = targetId - distance = cpt['TrkRange'] - self.pts[targetId].dRel = distance # from front of car - # From driver's pov, left is positive - self.pts[targetId].yRel = math.sin(cpt['TrkAzimuth'] * CV.DEG_TO_RAD) * distance - self.pts[targetId].vRel = cpt['TrkRangeRate'] - self.pts[targetId].aRel = float('nan') - self.pts[targetId].yvRel = float('nan') - - for oldTarget in list(self.pts.keys()): - if oldTarget not in currentTargets: - del self.pts[oldTarget] - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret diff --git a/selfdrive/car/gm/tests/__init__.py b/selfdrive/car/gm/tests/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/gm/tests/test_gm.py b/selfdrive/car/gm/tests/test_gm.py deleted file mode 100644 index a0a4a94ffa0455..00000000000000 --- a/selfdrive/car/gm/tests/test_gm.py +++ /dev/null @@ -1,20 +0,0 @@ -from parameterized import parameterized - -from openpilot.selfdrive.car.gm.fingerprints import FINGERPRINTS -from openpilot.selfdrive.car.gm.values import CAMERA_ACC_CAR, GM_RX_OFFSET - -CAMERA_DIAGNOSTIC_ADDRESS = 0x24b - - -class TestGMFingerprint: - @parameterized.expand(FINGERPRINTS.items()) - def test_can_fingerprints(self, car_model, fingerprints): - assert len(fingerprints) > 0 - - assert all(len(finger) for finger in fingerprints) - - # The camera can sometimes be communicating on startup - if car_model in CAMERA_ACC_CAR: - for finger in fingerprints: - for required_addr in (CAMERA_DIAGNOSTIC_ADDRESS, CAMERA_DIAGNOSTIC_ADDRESS + GM_RX_OFFSET): - assert finger.get(required_addr) == 8, required_addr diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py deleted file mode 100644 index 53a4621d27fe89..00000000000000 --- a/selfdrive/car/gm/values.py +++ /dev/null @@ -1,234 +0,0 @@ -from dataclasses import dataclass, field - -from cereal import car -from openpilot.selfdrive.car import dbc_dict, PlatformConfig, DbcDict, Platforms, CarSpecs -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output - STEER_STEP = 3 # Active control frames per command (~33hz) - INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) - STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness - STEER_DELTA_DOWN = 15 - STEER_DRIVER_ALLOWANCE = 65 - STEER_DRIVER_MULTIPLIER = 4 - STEER_DRIVER_FACTOR = 100 - NEAR_STOP_BRAKE_PHASE = 0.5 # m/s - - # Heartbeat for dash "Service Adaptive Cruise" and "Service Front Camera" - ADAS_KEEPALIVE_STEP = 100 - CAMERA_KEEPALIVE_STEP = 100 - - # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we - # perform the closed loop control, and might need some - # to apply some more braking if we're on a downhill slope. - # Our controller should still keep the 2 second average above - # -3.5 m/s^2 as per planner limits - ACCEL_MAX = 2. # m/s^2 - ACCEL_MIN = -4. # m/s^2 - - def __init__(self, CP): - # Gas/brake lookups - self.ZERO_GAS = 2048 # Coasting - self.MAX_BRAKE = 400 # ~ -4.0 m/s^2 with regen - - if CP.carFingerprint in CAMERA_ACC_CAR: - self.MAX_GAS = 3400 - self.MAX_ACC_REGEN = 1514 - self.INACTIVE_REGEN = 1554 - # Camera ACC vehicles have no regen while enabled. - # Camera transitions to MAX_ACC_REGEN from ZERO_GAS and uses friction brakes instantly - max_regen_acceleration = 0. - - else: - self.MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. - self.MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen - self.INACTIVE_REGEN = 1404 - # ICE has much less engine braking force compared to regen in EVs, - # lower threshold removes some braking deadzone - max_regen_acceleration = -1. if CP.carFingerprint in EV_CAR else -0.1 - - self.GAS_LOOKUP_BP = [max_regen_acceleration, 0., self.ACCEL_MAX] - self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, self.MAX_GAS] - - self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, max_regen_acceleration] - self.BRAKE_LOOKUP_V = [self.MAX_BRAKE, 0.] - - -@dataclass -class GMCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC)" - - def init_make(self, CP: car.CarParams): - if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera: - self.car_parts = CarParts.common([CarHarness.gm]) - else: - self.car_parts = CarParts.common([CarHarness.obd_ii]) - - -@dataclass(frozen=True, kw_only=True) -class GMCarSpecs(CarSpecs): - tireStiffnessFactor: float = 0.444 # not optimized yet - - -@dataclass -class GMPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) - - -@dataclass -class GMASCMPlatformConfig(GMPlatformConfig): - def init(self): - # ASCM is supported, but due to a janky install and hardware configuration, we are not showing in the car docs - self.car_docs = [] - - -class CAR(Platforms): - HOLDEN_ASTRA = GMASCMPlatformConfig( - [GMCarDocs("Holden Astra 2017")], - GMCarSpecs(mass=1363, wheelbase=2.662, steerRatio=15.7, centerToFrontRatio=0.4), - ) - CHEVROLET_VOLT = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ")], - GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=17.7, centerToFrontRatio=0.45, tireStiffnessFactor=0.469), - ) - CADILLAC_ATS = GMASCMPlatformConfig( - [GMCarDocs("Cadillac ATS Premium Performance 2018")], - GMCarSpecs(mass=1601, wheelbase=2.78, steerRatio=15.3), - ) - CHEVROLET_MALIBU = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Malibu Premier 2017")], - GMCarSpecs(mass=1496, wheelbase=2.83, steerRatio=15.8, centerToFrontRatio=0.4), - ) - GMC_ACADIA = GMASCMPlatformConfig( - [GMCarDocs("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], - GMCarSpecs(mass=1975, wheelbase=2.86, steerRatio=14.4, centerToFrontRatio=0.4), - ) - BUICK_LACROSSE = GMASCMPlatformConfig( - [GMCarDocs("Buick LaCrosse 2017-19", "Driver Confidence Package 2")], - GMCarSpecs(mass=1712, wheelbase=2.91, steerRatio=15.8, centerToFrontRatio=0.4), - ) - BUICK_REGAL = GMASCMPlatformConfig( - [GMCarDocs("Buick Regal Essence 2018")], - GMCarSpecs(mass=1714, wheelbase=2.83, steerRatio=14.4, centerToFrontRatio=0.4), - ) - CADILLAC_ESCALADE = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade 2017", "Driver Assist Package")], - GMCarSpecs(mass=2564, wheelbase=2.95, steerRatio=17.3), - ) - CADILLAC_ESCALADE_ESV = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS")], - GMCarSpecs(mass=2739, wheelbase=3.302, steerRatio=17.3, tireStiffnessFactor=1.0), - ) - CADILLAC_ESCALADE_ESV_2019 = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade ESV 2019", "Adaptive Cruise Control (ACC) & LKAS")], - CADILLAC_ESCALADE_ESV.specs, - ) - CHEVROLET_BOLT_EUV = GMPlatformConfig( - [ - GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), - GMCarDocs("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), - ], - GMCarSpecs(mass=1669, wheelbase=2.63779, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), - ) - CHEVROLET_SILVERADO = GMPlatformConfig( - [ - GMCarDocs("Chevrolet Silverado 1500 2020-21", "Safety Package II"), - GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), - ], - GMCarSpecs(mass=2450, wheelbase=3.75, steerRatio=16.3, tireStiffnessFactor=1.0), - ) - CHEVROLET_EQUINOX = GMPlatformConfig( - [GMCarDocs("Chevrolet Equinox 2019-22")], - GMCarSpecs(mass=1588, wheelbase=2.72, steerRatio=14.4, centerToFrontRatio=0.4), - ) - CHEVROLET_TRAILBLAZER = GMPlatformConfig( - [GMCarDocs("Chevrolet Trailblazer 2021-22")], - GMCarSpecs(mass=1345, wheelbase=2.64, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), - ) - - -class CruiseButtons: - INIT = 0 - UNPRESS = 1 - RES_ACCEL = 2 - DECEL_SET = 3 - MAIN = 5 - CANCEL = 6 - -class AccState: - OFF = 0 - ACTIVE = 1 - FAULTED = 3 - STANDSTILL = 4 - -class CanBus: - POWERTRAIN = 0 - OBSTACLE = 1 - CAMERA = 2 - CHASSIS = 2 - LOOPBACK = 128 - DROPPED = 192 - - -# In a Data Module, an identifier is a string used to recognize an object, -# either by itself or together with the identifiers of parent objects. -# Each returns a 4 byte hex representation of the decimal part number. `b"\x02\x8c\xf0'"` -> 42790951 -GM_BOOT_SOFTWARE_PART_NUMER_REQUEST = b'\x1a\xc0' # likely does not contain anything useful -GM_SOFTWARE_MODULE_1_REQUEST = b'\x1a\xc1' -GM_SOFTWARE_MODULE_2_REQUEST = b'\x1a\xc2' -GM_SOFTWARE_MODULE_3_REQUEST = b'\x1a\xc3' - -# Part number of XML data file that is used to configure ECU -GM_XML_DATA_FILE_PART_NUMBER = b'\x1a\x9c' -GM_XML_CONFIG_COMPAT_ID = b'\x1a\x9b' # used to know if XML file is compatible with the ECU software/hardware - -# This DID is for identifying the part number that reflects the mix of hardware, -# software, and calibrations in the ECU when it first arrives at the vehicle assembly plant. -# If there's an Alpha Code, it's associated with this part number and stored in the DID $DB. -GM_END_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcb' -GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdb' -GM_BASE_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcc' -GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdc' -GM_FW_RESPONSE = b'\x5a' - -GM_FW_REQUESTS = [ - GM_BOOT_SOFTWARE_PART_NUMER_REQUEST, - GM_SOFTWARE_MODULE_1_REQUEST, - GM_SOFTWARE_MODULE_2_REQUEST, - GM_SOFTWARE_MODULE_3_REQUEST, - GM_XML_DATA_FILE_PART_NUMBER, - GM_XML_CONFIG_COMPAT_ID, - GM_END_MODEL_PART_NUMBER_REQUEST, - GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, - GM_BASE_MODEL_PART_NUMBER_REQUEST, - GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, -] - -GM_RX_OFFSET = 0x400 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for req in GM_FW_REQUESTS for request in [ - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, req], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, GM_FW_RESPONSE + bytes([req[-1]])], - rx_offset=GM_RX_OFFSET, - bus=0, - logging=True, - ), - ]], - extra_ecus=[(Ecu.fwdCamera, 0x24b, None)], -) - -EV_CAR = {CAR.CHEVROLET_VOLT, CAR.CHEVROLET_BOLT_EUV} - -# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.CHEVROLET_BOLT_EUV, CAR.CHEVROLET_SILVERADO, CAR.CHEVROLET_EQUINOX, CAR.CHEVROLET_TRAILBLAZER} - -STEER_THRESHOLD = 1.0 - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/helpers.py b/selfdrive/car/helpers.py deleted file mode 100644 index 81f6d6a6bcc07e..00000000000000 --- a/selfdrive/car/helpers.py +++ /dev/null @@ -1,22 +0,0 @@ -def clip(x, lo, hi): - return max(lo, min(hi, x)) - - -def interp(x, xp, fp): - N = len(xp) - - def get_interp(xv): - hi = 0 - while hi < N and xv > xp[hi]: - hi += 1 - low = hi - 1 - return fp[-1] if hi == N and xv > xp[low] else ( - fp[0] if hi == 0 else - (xv - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) - - return [get_interp(v) for v in x] if hasattr(x, '__iter__') else get_interp(x) - - -def mean(x): - return sum(x) / len(x) - diff --git a/selfdrive/car/honda/__init__.py b/selfdrive/car/honda/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py deleted file mode 100644 index 0f08ee21a86915..00000000000000 --- a/selfdrive/car/honda/carcontroller.py +++ /dev/null @@ -1,254 +0,0 @@ -from collections import namedtuple - -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import DT_CTRL, rate_limit, make_tester_present_msg -from openpilot.selfdrive.car.helpers import clip, interp -from openpilot.selfdrive.car.honda import hondacan -from openpilot.selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - - -def compute_gb_honda_bosch(accel, speed): - # TODO returns 0s, is unused - return 0.0, 0.0 - - -def compute_gb_honda_nidec(accel, speed): - creep_brake = 0.0 - creep_speed = 2.3 - creep_brake_value = 0.15 - if speed < creep_speed: - creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value - gb = float(accel) / 4.8 - creep_brake - return clip(gb, 0.0, 1.0), clip(-gb, 0.0, 1.0) - - -def compute_gas_brake(accel, speed, fingerprint): - if fingerprint in HONDA_BOSCH: - return compute_gb_honda_bosch(accel, speed) - else: - return compute_gb_honda_nidec(accel, speed) - - -# TODO not clear this does anything useful -def actuator_hysteresis(brake, braking, brake_steady, v_ego, car_fingerprint): - # hyst params - brake_hyst_on = 0.02 # to activate brakes exceed this value - brake_hyst_off = 0.005 # to deactivate brakes below this value - brake_hyst_gap = 0.01 # don't change brake command for small oscillations within this value - - # *** hysteresis logic to avoid brake blinking. go above 0.1 to trigger - if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: - brake = 0. - braking = brake > 0. - - # for small brake oscillations within brake_hyst_gap, don't change the brake command - if brake == 0.: - brake_steady = 0. - elif brake > brake_steady + brake_hyst_gap: - brake_steady = brake - brake_hyst_gap - elif brake < brake_steady - brake_hyst_gap: - brake_steady = brake + brake_hyst_gap - brake = brake_steady - - return brake, braking, brake_steady - - -def brake_pump_hysteresis(apply_brake, apply_brake_last, last_pump_ts, ts): - pump_on = False - - # reset pump timer if: - # - there is an increment in brake request - # - we are applying steady state brakes and we haven't been running the pump - # for more than 20s (to prevent pressure bleeding) - if apply_brake > apply_brake_last or (ts - last_pump_ts > 20. and apply_brake > 0): - last_pump_ts = ts - - # once the pump is on, run it for at least 0.2s - if ts - last_pump_ts < 0.2 and apply_brake > 0: - pump_on = True - - return pump_on, last_pump_ts - - -def process_hud_alert(hud_alert): - # initialize to no alert - fcw_display = 0 - steer_required = 0 - acc_alert = 0 - - # priority is: FCW, steer required, all others - if hud_alert == VisualAlert.fcw: - fcw_display = VISUAL_HUD[hud_alert.raw] - elif hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): - steer_required = VISUAL_HUD[hud_alert.raw] - else: - acc_alert = VISUAL_HUD[hud_alert.raw] - - return fcw_display, steer_required, acc_alert - - -HUDData = namedtuple("HUDData", - ["pcm_accel", "v_cruise", "lead_visible", - "lanes_visible", "fcw", "acc_alert", "steer_required", "lead_distance_bars"]) - - -def rate_limit_steer(new_steer, last_steer): - # TODO just hardcoded ramp to min/max in 0.33s for all Honda - MAX_DELTA = 3 * DT_CTRL - return clip(new_steer, last_steer - MAX_DELTA, last_steer + MAX_DELTA) - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.packer = CANPacker(dbc_name) - self.params = CarControllerParams(CP) - self.CAN = hondacan.CanBus(CP) - - self.braking = False - self.brake_steady = 0. - self.brake_last = 0. - self.apply_brake_last = 0 - self.last_pump_ts = 0. - self.stopping_counter = 0 - - self.accel = 0.0 - self.speed = 0.0 - self.gas = 0.0 - self.brake = 0.0 - self.last_steer = 0.0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - conversion = hondacan.get_cruise_speed_conversion(self.CP.carFingerprint, CS.is_metric) - hud_v_cruise = hud_control.setSpeed / conversion if hud_control.speedVisible else 255 - pcm_cancel_cmd = CC.cruiseControl.cancel - - if CC.longActive: - accel = actuators.accel - gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, self.CP.carFingerprint) - else: - accel = 0.0 - gas, brake = 0.0, 0.0 - - # *** rate limit steer *** - limited_steer = rate_limit_steer(actuators.steer, self.last_steer) - self.last_steer = limited_steer - - # *** apply brake hysteresis *** - pre_limit_brake, self.braking, self.brake_steady = actuator_hysteresis(brake, self.braking, self.brake_steady, - CS.out.vEgo, self.CP.carFingerprint) - - # *** rate limit after the enable check *** - self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL) - - # vehicle hud display, wait for one update from 10Hz 0x304 msg - fcw_display, steer_required, acc_alert = process_hud_alert(hud_control.visualAlert) - - # **** process the car messages **** - - # steer torque is converted back to CAN reference (positive when steering right) - apply_steer = int(interp(-limited_steer * self.params.STEER_MAX, - self.params.STEER_LOOKUP_BP, self.params.STEER_LOOKUP_V)) - - # Send CAN commands - can_sends = [] - - # tester present - w/ no response (keeps radar disabled) - if self.CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and self.CP.openpilotLongitudinalControl: - if self.frame % 10 == 0: - can_sends.append(make_tester_present_msg(0x18DAB0F1, 1, suppress_response=True)) - - # Send steering command. - can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_steer, CC.latActive, self.CP.carFingerprint, - CS.CP.openpilotLongitudinalControl)) - - # wind brake from air resistance decel at high speed - wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) - # all of this is only relevant for HONDA NIDEC - max_accel = interp(CS.out.vEgo, self.params.NIDEC_MAX_ACCEL_BP, self.params.NIDEC_MAX_ACCEL_V) - # TODO this 1.44 is just to maintain previous behavior - pcm_speed_BP = [-wind_brake, - -wind_brake * (3 / 4), - 0.0, - 0.5] - # The Honda ODYSSEY seems to have different PCM_ACCEL - # msgs, is it other cars too? - if not CC.longActive: - pcm_speed = 0.0 - pcm_accel = int(0.0) - elif self.CP.carFingerprint in HONDA_NIDEC_ALT_PCM_ACCEL: - pcm_speed_V = [0.0, - clip(CS.out.vEgo - 3.0, 0.0, 100.0), - clip(CS.out.vEgo + 0.0, 0.0, 100.0), - clip(CS.out.vEgo + 5.0, 0.0, 100.0)] - pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) - pcm_accel = int(1.0 * self.params.NIDEC_GAS_MAX) - else: - pcm_speed_V = [0.0, - clip(CS.out.vEgo - 2.0, 0.0, 100.0), - clip(CS.out.vEgo + 2.0, 0.0, 100.0), - clip(CS.out.vEgo + 5.0, 0.0, 100.0)] - pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) - pcm_accel = int(clip((accel / 1.44) / max_accel, 0.0, 1.0) * self.params.NIDEC_GAS_MAX) - - if not self.CP.openpilotLongitudinalControl: - if self.frame % 2 == 0 and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: # radarless cars don't have supplemental message - can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, self.CAN, self.CP.carFingerprint)) - # If using stock ACC, spam cancel command to kill gas when OP disengages. - if pcm_cancel_cmd: - can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.CANCEL, self.CP.carFingerprint)) - elif CC.cruiseControl.resume: - can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) - - else: - # Send gas and brake commands. - if self.frame % 2 == 0: - ts = self.frame * DT_CTRL - - if self.CP.carFingerprint in HONDA_BOSCH: - self.accel = clip(accel, self.params.BOSCH_ACCEL_MIN, self.params.BOSCH_ACCEL_MAX) - self.gas = interp(accel, self.params.BOSCH_GAS_LOOKUP_BP, self.params.BOSCH_GAS_LOOKUP_V) - - stopping = actuators.longControlState == LongCtrlState.stopping - self.stopping_counter = self.stopping_counter + 1 if stopping else 0 - can_sends.extend(hondacan.create_acc_commands(self.packer, self.CAN, CC.enabled, CC.longActive, self.accel, self.gas, - self.stopping_counter, self.CP.carFingerprint)) - else: - apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) - apply_brake = int(clip(apply_brake * self.params.NIDEC_BRAKE_MAX, 0, self.params.NIDEC_BRAKE_MAX - 1)) - pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) - - pcm_override = True - can_sends.append(hondacan.create_brake_command(self.packer, self.CAN, apply_brake, pump_on, - pcm_override, pcm_cancel_cmd, fcw_display, - self.CP.carFingerprint, CS.stock_brake)) - self.apply_brake_last = apply_brake - self.brake = apply_brake / self.params.NIDEC_BRAKE_MAX - - # Send dashboard UI commands. - if self.frame % 10 == 0: - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, - hud_control.lanesVisible, fcw_display, acc_alert, steer_required, hud_control.leadDistanceBars) - can_sends.extend(hondacan.create_ui_commands(self.packer, self.CAN, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, CS.acc_hud, CS.lkas_hud)) - - if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: - self.speed = pcm_speed - self.gas = pcm_accel / self.params.NIDEC_GAS_MAX - - new_actuators = actuators.as_builder() - new_actuators.speed = self.speed - new_actuators.accel = self.accel - new_actuators.gas = self.gas - new_actuators.brake = self.brake - new_actuators.steer = self.last_steer - new_actuators.steerOutputCan = apply_steer - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py deleted file mode 100644 index 956e6a3bd3e022..00000000000000 --- a/selfdrive/car/honda/carstate.py +++ /dev/null @@ -1,297 +0,0 @@ -from collections import defaultdict - -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.helpers import interp -from openpilot.selfdrive.car.honda.hondacan import CanBus, get_cruise_speed_conversion -from openpilot.selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ - HondaFlags -from openpilot.selfdrive.car.interfaces import CarStateBase - -TransmissionType = car.CarParams.TransmissionType - - -def get_can_messages(CP, gearbox_msg): - messages = [ - ("ENGINE_DATA", 100), - ("WHEEL_SPEEDS", 50), - ("STEERING_SENSORS", 100), - ("SEATBELT_STATUS", 10), - ("CRUISE", 10), - ("POWERTRAIN_DATA", 100), - ("CAR_SPEED", 10), - ("VSA_STATUS", 50), - ("STEER_STATUS", 100), - ("STEER_MOTOR_TORQUE", 0), # TODO: not on every car - ] - - if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: - messages += [ - ("SCM_FEEDBACK", 25), - ("SCM_BUTTONS", 50), - ] - else: - messages += [ - ("SCM_FEEDBACK", 10), - ("SCM_BUTTONS", 25), - ] - - if CP.carFingerprint in (CAR.HONDA_CRV_HYBRID, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): - messages.append((gearbox_msg, 50)) - else: - messages.append((gearbox_msg, 100)) - - if CP.flags & HondaFlags.BOSCH_ALT_BRAKE: - messages.append(("BRAKE_MODULE", 50)) - - if CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): - messages.append(("EPB_STATUS", 50)) - - if CP.carFingerprint in HONDA_BOSCH: - # these messages are on camera bus on radarless cars - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - messages += [ - ("ACC_HUD", 10), - ("ACC_CONTROL", 50), - ] - else: # Nidec signals - if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: - messages.append(("CRUISE_PARAMS", 10)) - else: - messages.append(("CRUISE_PARAMS", 50)) - - # TODO: clean this up - if CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - pass - elif CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - pass - else: - messages.append(("DOORS_STATUS", 3)) - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - messages.append(("CRUISE_FAULT_STATUS", 50)) - elif CP.openpilotLongitudinalControl: - messages.append(("STANDSTILL", 50)) - - return messages - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.gearbox_msg = "GEARBOX" - if CP.carFingerprint == CAR.HONDA_ACCORD and CP.transmissionType == TransmissionType.cvt: - self.gearbox_msg = "GEARBOX_15T" - - self.main_on_sig_msg = "SCM_FEEDBACK" - if CP.carFingerprint in HONDA_NIDEC_ALT_SCM_MESSAGES: - self.main_on_sig_msg = "SCM_BUTTONS" - - self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"] - self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"]) - - self.brake_switch_prev = False - self.brake_switch_active = False - self.cruise_setting = 0 - self.v_cruise_pcm_prev = 0 - - # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster - # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) - self.dash_speed_seen = False - - def update(self, cp, cp_cam, cp_body): - ret = car.CarState.new_message() - - # car params - v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping - v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero - - # update prevs, update must run once per loop - self.prev_cruise_buttons = self.cruise_buttons - self.prev_cruise_setting = self.cruise_setting - self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] - self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"] - - # used for car hud message - self.is_metric = not cp.vl["CAR_SPEED"]["IMPERIAL_UNIT"] - - # ******************* parse out can ******************* - # STANDSTILL->WHEELS_MOVING bit can be noisy around zero, so use XMISSION_SPEED - # panda checks if the signal is non-zero - ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 - # TODO: find a common signal across all cars - if self.CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) - elif self.CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) - else: - ret.doorOpen = any([cp.vl["DOORS_STATUS"]["DOOR_OPEN_FL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_FR"], - cp.vl["DOORS_STATUS"]["DOOR_OPEN_RL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"]) - - steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]["STEER_STATUS"]] - ret.steerFaultPermanent = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT") - # LOW_SPEED_LOCKOUT is not worth a warning - # NO_TORQUE_ALERT_2 can be caused by bump or steering nudge from driver - ret.steerFaultTemporary = steer_status not in ("NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2") - - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - ret.accFaulted = bool(cp.vl["CRUISE_FAULT_STATUS"]["CRUISE_FAULT"]) - else: - # On some cars, these two signals are always 1, this flag is masking a bug in release - # FIXME: find and set the ACC faulted signals on more platforms - if self.CP.openpilotLongitudinalControl: - ret.accFaulted = bool(cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"]) - - # Log non-critical stock ACC/LKAS faults if Nidec (camera) - if self.CP.carFingerprint not in HONDA_BOSCH: - ret.carFaultedNonCritical = bool(cp_cam.vl["ACC_HUD"]["ACC_PROBLEM"] or cp_cam.vl["LKAS_HUD"]["LKAS_PROBLEM"]) - - ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], - ) - v_wheel = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.0 - - # blend in transmission speed at low speed, since it has more low speed accuracy - v_weight = interp(v_wheel, v_weight_bp, v_weight_v) - ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * self.CP.wheelSpeedFactor + v_weight * v_wheel - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - - self.dash_speed_seen = self.dash_speed_seen or cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] > 1e-3 - if self.dash_speed_seen: - conversion = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - ret.vEgoCluster = cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] * conversion - - ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"] - ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"] - - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( - 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) - ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 - - # TODO: set for all cars - if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): - ret.parkingBrake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 - - gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None)) - - ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] - ret.gasPressed = ret.gas > 1e-5 - - ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"] - ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD.get(self.CP.carFingerprint, 1200) - - if self.CP.carFingerprint in HONDA_BOSCH: - # The PCM always manages its own cruise control state, but doesn't publish it - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - ret.cruiseState.nonAdaptive = cp_cam.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 - - if not self.CP.openpilotLongitudinalControl: - # ACC_HUD is on camera bus on radarless cars - acc_hud = cp_cam.vl["ACC_HUD"] if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS else cp.vl["ACC_HUD"] - ret.cruiseState.nonAdaptive = acc_hud["CRUISE_CONTROL_LABEL"] != 0 - ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. - - conversion = get_cruise_speed_conversion(self.CP.carFingerprint, self.is_metric) - # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. - ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion - self.v_cruise_pcm_prev = ret.cruiseState.speed - else: - ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS - - if self.CP.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 - else: - # brake switch has shown some single time step noise, so only considered when - # switch is on for at least 2 consecutive CAN samples - # brake switch rises earlier than brake pressed but is never 1 when in park - brake_switch_vals = cp.vl_all["POWERTRAIN_DATA"]["BRAKE_SWITCH"] - if len(brake_switch_vals): - brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 - if len(brake_switch_vals) > 1: - self.brake_switch_prev = brake_switch_vals[-2] != 0 - self.brake_switch_active = brake_switch and self.brake_switch_prev - self.brake_switch_prev = brake_switch - ret.brakePressed = (cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] != 0) or self.brake_switch_active - - ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] - ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 - ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) - - # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models - if self.CP.carFingerprint in (CAR.HONDA_PILOT, CAR.HONDA_RIDGELINE): - if ret.brake > 0.1: - ret.brakePressed = True - - if self.CP.carFingerprint in HONDA_BOSCH: - # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts - if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) - else: - ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) - - self.acc_hud = False - self.lkas_hud = False - if self.CP.carFingerprint not in HONDA_BOSCH: - ret.stockFcw = cp_cam.vl["BRAKE_COMMAND"]["FCW"] != 0 - self.acc_hud = cp_cam.vl["ACC_HUD"] - self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - self.lkas_hud = cp_cam.vl["LKAS_HUD"] - - if self.CP.enableBsm: - # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 - # more info here: https://github.com/commaai/openpilot/pull/1867 - ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 - ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]["BSM_ALERT"] == 1 - - return ret - - def get_can_parser(self, CP): - messages = get_can_messages(CP, self.gearbox_msg) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).pt) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - ("STEERING_CONTROL", 100), - ] - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - messages += [ - ("ACC_HUD", 10), - ("LKAS_HUD", 10), - ] - - elif CP.carFingerprint not in HONDA_BOSCH: - messages += [ - ("ACC_HUD", 10), - ("LKAS_HUD", 10), - ("BRAKE_COMMAND", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) - - @staticmethod - def get_body_can_parser(CP): - if CP.enableBsm: - messages = [ - ("BSM_STATUS_LEFT", 3), - ("BSM_STATUS_RIGHT", 3), - ] - bus_body = CanBus(CP).radar # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) - return CANParser(DBC[CP.carFingerprint]["body"], messages, bus_body) - return None diff --git a/selfdrive/car/honda/fingerprints.py b/selfdrive/car/honda/fingerprints.py deleted file mode 100644 index 191fd8e44a159b..00000000000000 --- a/selfdrive/car/honda/fingerprints.py +++ /dev/null @@ -1,899 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.honda.values import CAR - -Ecu = car.CarParams.Ecu - -# Modified FW can be identified by the second dash being replaced by a comma -# For example: `b'39990-TVA,A150\x00\x00'` -# -# TODO: vsa is "essential" for fpv2 but doesn't appear on some CAR.FREED models - - -FW_VERSIONS = { - CAR.HONDA_ACCORD: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TVC-A910\x00\x00', - b'54008-TWA-A910\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6A7-A220\x00\x00', - b'28101-6A7-A230\x00\x00', - b'28101-6A7-A320\x00\x00', - b'28101-6A7-A330\x00\x00', - b'28101-6A7-A410\x00\x00', - b'28101-6A7-A510\x00\x00', - b'28101-6A7-A610\x00\x00', - b'28101-6A7-A710\x00\x00', - b'28101-6A9-H140\x00\x00', - b'28101-6A9-H420\x00\x00', - b'28102-6B8-A560\x00\x00', - b'28102-6B8-A570\x00\x00', - b'28102-6B8-A700\x00\x00', - b'28102-6B8-A800\x00\x00', - b'28102-6B8-C560\x00\x00', - b'28102-6B8-C570\x00\x00', - b'28102-6B8-M520\x00\x00', - b'28102-6B8-R700\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TVA-A050\x00\x00', - b'46114-TVA-A060\x00\x00', - b'46114-TVA-A080\x00\x00', - b'46114-TVA-A120\x00\x00', - b'46114-TVA-A320\x00\x00', - b'46114-TVE-H550\x00\x00', - b'46114-TVE-H560\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TVA-B040\x00\x00', - b'57114-TVA-B050\x00\x00', - b'57114-TVA-B060\x00\x00', - b'57114-TVA-B530\x00\x00', - b'57114-TVA-C040\x00\x00', - b'57114-TVA-C050\x00\x00', - b'57114-TVA-C060\x00\x00', - b'57114-TVA-C530\x00\x00', - b'57114-TVA-E520\x00\x00', - b'57114-TVE-H250\x00\x00', - b'57114-TWA-A040\x00\x00', - b'57114-TWA-A050\x00\x00', - b'57114-TWA-A530\x00\x00', - b'57114-TWA-B520\x00\x00', - b'57114-TWA-C510\x00\x00', - b'57114-TWB-H030\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBX-H120\x00\x00', - b'39990-TVA,A150\x00\x00', - b'39990-TVA-A140\x00\x00', - b'39990-TVA-A150\x00\x00', - b'39990-TVA-A160\x00\x00', - b'39990-TVA-A340\x00\x00', - b'39990-TVA-X030\x00\x00', - b'39990-TVA-X040\x00\x00', - b'39990-TVE-H130\x00\x00', - b'39990-TWB-H120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBX-H230\x00\x00', - b'77959-TVA-A460\x00\x00', - b'77959-TVA-F330\x00\x00', - b'77959-TVA-H230\x00\x00', - b'77959-TVA-L420\x00\x00', - b'77959-TVA-X330\x00\x00', - b'77959-TWA-A440\x00\x00', - b'77959-TWA-L420\x00\x00', - b'77959-TWB-H220\x00\x00', - ], - (Ecu.hud, 0x18da61f1, None): [ - b'78209-TVA-A010\x00\x00', - b'78209-TVA-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBX-H140\x00\x00', - b'36802-TVA-A150\x00\x00', - b'36802-TVA-A160\x00\x00', - b'36802-TVA-A170\x00\x00', - b'36802-TVA-A180\x00\x00', - b'36802-TVA-A330\x00\x00', - b'36802-TVC-A330\x00\x00', - b'36802-TVE-H070\x00\x00', - b'36802-TWA-A070\x00\x00', - b'36802-TWA-A080\x00\x00', - b'36802-TWA-A210\x00\x00', - b'36802-TWA-A330\x00\x00', - b'36802-TWB-H060\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBX-H130\x00\x00', - b'36161-TVA-A060\x00\x00', - b'36161-TVA-A330\x00\x00', - b'36161-TVC-A330\x00\x00', - b'36161-TVE-H050\x00\x00', - b'36161-TWA-A070\x00\x00', - b'36161-TWA-A330\x00\x00', - b'36161-TWB-H040\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TVA-A010\x00\x00', - b'38897-TVA-A020\x00\x00', - b'38897-TVA-A230\x00\x00', - b'38897-TVA-A240\x00\x00', - b'38897-TWA-A120\x00\x00', - b'38897-TWD-J020\x00\x00', - ], - }, - CAR.HONDA_CIVIC: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A040\x00\x00', - b'28101-5CG-A050\x00\x00', - b'28101-5CG-A070\x00\x00', - b'28101-5CG-A080\x00\x00', - b'28101-5CG-A320\x00\x00', - b'28101-5CG-A810\x00\x00', - b'28101-5CG-A820\x00\x00', - b'28101-5DJ-A040\x00\x00', - b'28101-5DJ-A060\x00\x00', - b'28101-5DJ-A510\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBA-A540\x00\x00', - b'57114-TBA-A550\x00\x00', - b'57114-TBA-A560\x00\x00', - b'57114-TBA-A570\x00\x00', - b'57114-TEA-Q220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA,A030\x00\x00', - b'39990-TBA-A030\x00\x00', - b'39990-TBG-A030\x00\x00', - b'39990-TEA-T020\x00\x00', - b'39990-TEG-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A030\x00\x00', - b'77959-TBA-A040\x00\x00', - b'77959-TBG-A020\x00\x00', - b'77959-TBG-A030\x00\x00', - b'77959-TEA-Q820\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TBA-A020\x00\x00', - b'36161-TBA-A030\x00\x00', - b'36161-TBA-A040\x00\x00', - b'36161-TBC-A020\x00\x00', - b'36161-TBC-A030\x00\x00', - b'36161-TED-Q320\x00\x00', - b'36161-TEG-A010\x00\x00', - b'36161-TEG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A010\x00\x00', - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.HONDA_CIVIC_BOSCH: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A920\x00\x00', - b'28101-5CG-AB10\x00\x00', - b'28101-5CG-C110\x00\x00', - b'28101-5CG-C220\x00\x00', - b'28101-5CG-C320\x00\x00', - b'28101-5CG-G020\x00\x00', - b'28101-5CG-L020\x00\x00', - b'28101-5CK-A130\x00\x00', - b'28101-5CK-A140\x00\x00', - b'28101-5CK-A150\x00\x00', - b'28101-5CK-C130\x00\x00', - b'28101-5CK-C140\x00\x00', - b'28101-5CK-C150\x00\x00', - b'28101-5CK-G210\x00\x00', - b'28101-5CK-J710\x00\x00', - b'28101-5CK-Q610\x00\x00', - b'28101-5DJ-A610\x00\x00', - b'28101-5DJ-A710\x00\x00', - b'28101-5DV-E330\x00\x00', - b'28101-5DV-E610\x00\x00', - b'28101-5DV-E820\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBG-A330\x00\x00', - b'57114-TBG-A340\x00\x00', - b'57114-TBG-A350\x00\x00', - b'57114-TGG-A340\x00\x00', - b'57114-TGG-C320\x00\x00', - b'57114-TGG-G320\x00\x00', - b'57114-TGG-L320\x00\x00', - b'57114-TGG-L330\x00\x00', - b'57114-TGH-L130\x00\x00', - b'57114-TGK-T320\x00\x00', - b'57114-TGL-G330\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA-C020\x00\x00', - b'39990-TBA-C120\x00\x00', - b'39990-TEA-T820\x00\x00', - b'39990-TEZ-T020\x00\x00', - b'39990-TGG,A020\x00\x00', - b'39990-TGG,A120\x00\x00', - b'39990-TGG-A020\x00\x00', - b'39990-TGG-A120\x00\x00', - b'39990-TGG-J510\x00\x00', - b'39990-TGH-J530\x00\x00', - b'39990-TGL-E130\x00\x00', - b'39990-TGN-E120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A060\x00\x00', - b'77959-TBG-A050\x00\x00', - b'77959-TEA-G020\x00\x00', - b'77959-TGG-A020\x00\x00', - b'77959-TGG-A030\x00\x00', - b'77959-TGG-E010\x00\x00', - b'77959-TGG-G010\x00\x00', - b'77959-TGG-G110\x00\x00', - b'77959-TGG-J320\x00\x00', - b'77959-TGG-Z820\x00\x00', - b'77959-TGH-J110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBA-A150\x00\x00', - b'36802-TBA-A160\x00\x00', - b'36802-TFJ-G060\x00\x00', - b'36802-TGG-A050\x00\x00', - b'36802-TGG-A060\x00\x00', - b'36802-TGG-A070\x00\x00', - b'36802-TGG-A130\x00\x00', - b'36802-TGG-G040\x00\x00', - b'36802-TGG-G130\x00\x00', - b'36802-TGH-A140\x00\x00', - b'36802-TGK-Q120\x00\x00', - b'36802-TGL-G040\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBA-A130\x00\x00', - b'36161-TBA-A140\x00\x00', - b'36161-TFJ-G070\x00\x00', - b'36161-TGG-A060\x00\x00', - b'36161-TGG-A080\x00\x00', - b'36161-TGG-A120\x00\x00', - b'36161-TGG-G050\x00\x00', - b'36161-TGG-G070\x00\x00', - b'36161-TGG-G130\x00\x00', - b'36161-TGG-G140\x00\x00', - b'36161-TGH-A140\x00\x00', - b'36161-TGK-Q120\x00\x00', - b'36161-TGL-G050\x00\x00', - b'36161-TGL-G070\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - b'38897-TBA-A110\x00\x00', - b'38897-TGH-A010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'39494-TGL-G030\x00\x00', - ], - }, - CAR.HONDA_CIVIC_BOSCH_DIESEL: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-59Y-G220\x00\x00', - b'28101-59Y-G620\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TGN-E320\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TFK-G020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TFK-G210\x00\x00', - b'77959-TGN-G220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TFK-G130\x00\x00', - b'36802-TGN-G130\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TGN-E010\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TFK-G130\x00\x00', - b'36161-TGN-G130\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.HONDA_CRV: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1W-A230\x00\x00', - b'57114-T1W-A240\x00\x00', - b'57114-TFF-A940\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T0A-A230\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1W-A830\x00\x00', - b'36161-T1W-C830\x00\x00', - b'36161-T1X-A830\x00\x00', - ], - }, - CAR.HONDA_CRV_5G: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5RG-A020\x00\x00', - b'28101-5RG-A030\x00\x00', - b'28101-5RG-A040\x00\x00', - b'28101-5RG-A120\x00\x00', - b'28101-5RG-A220\x00\x00', - b'28101-5RH-A020\x00\x00', - b'28101-5RH-A030\x00\x00', - b'28101-5RH-A040\x00\x00', - b'28101-5RH-A120\x00\x00', - b'28101-5RH-A220\x00\x00', - b'28101-5RL-Q010\x00\x00', - b'28101-5RM-F010\x00\x00', - b'28101-5RM-K010\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TLA-A040\x00\x00', - b'57114-TLA-A050\x00\x00', - b'57114-TLA-A060\x00\x00', - b'57114-TLB-A830\x00\x00', - b'57114-TMC-Z040\x00\x00', - b'57114-TMC-Z050\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TLA,A040\x00\x00', - b'39990-TLA-A040\x00\x00', - b'39990-TLA-A110\x00\x00', - b'39990-TLA-A220\x00\x00', - b'39990-TME-T030\x00\x00', - b'39990-TME-T120\x00\x00', - b'39990-TMT-T010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TLA-A040\x00\x00', - b'46114-TLA-A050\x00\x00', - b'46114-TLA-A930\x00\x00', - b'46114-TMC-U020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TLA-A010\x00\x00', - b'38897-TLA-A110\x00\x00', - b'38897-TNY-G010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TLA-A040\x00\x00', - b'36802-TLA-A050\x00\x00', - b'36802-TLA-A060\x00\x00', - b'36802-TLA-A070\x00\x00', - b'36802-TMC-Q040\x00\x00', - b'36802-TMC-Q070\x00\x00', - b'36802-TNY-A030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TLA-A060\x00\x00', - b'36161-TLA-A070\x00\x00', - b'36161-TLA-A080\x00\x00', - b'36161-TMC-Q020\x00\x00', - b'36161-TMC-Q030\x00\x00', - b'36161-TMC-Q040\x00\x00', - b'36161-TNY-A020\x00\x00', - b'36161-TNY-A030\x00\x00', - b'36161-TNY-A040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-A240\x00\x00', - b'77959-TLA-A250\x00\x00', - b'77959-TLA-A320\x00\x00', - b'77959-TLA-A410\x00\x00', - b'77959-TLA-A420\x00\x00', - b'77959-TLA-Q040\x00\x00', - b'77959-TLA-Z040\x00\x00', - b'77959-TMM-F040\x00\x00', - ], - }, - CAR.HONDA_CRV_EU: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1V-G920\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1V-G520\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-T1V-G010\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5LH-E120\x00\x00', - b'28103-5LH-E100\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T1G-G940\x00\x00', - ], - }, - CAR.HONDA_CRV_HYBRID: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TMB-H030\x00\x00', - b'57114-TPA-G020\x00\x00', - b'57114-TPG-A020\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TMA-H020\x00\x00', - b'39990-TPA-G030\x00\x00', - b'39990-TPG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TMA-H110\x00\x00', - b'38897-TPG-A110\x00\x00', - b'38897-TPG-A210\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TMB-H510\x00\x00', - b'54008-TMB-H610\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TMB-H040\x00\x00', - b'36161-TPA-E050\x00\x00', - b'36161-TPG-A030\x00\x00', - b'36161-TPG-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TMB-H040\x00\x00', - b'36802-TPA-E040\x00\x00', - b'36802-TPG-A020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-C320\x00\x00', - b'77959-TLA-C410\x00\x00', - b'77959-TLA-C420\x00\x00', - b'77959-TLA-G220\x00\x00', - b'77959-TLA-H240\x00\x00', - ], - }, - CAR.HONDA_FIT: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T5R-L020\x00\x00', - b'57114-T5R-L220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T5R-C020\x00\x00', - b'39990-T5R-C030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T5A-J010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T5R-A040\x00\x00', - b'36161-T5R-A240\x00\x00', - b'36161-T5R-A520\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T5R-A230\x00\x00', - ], - }, - CAR.HONDA_FREED: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TDK-J010\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TDK-J050\x00\x00', - b'39990-TDK-N020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TDK-J120\x00\x00', - b'57114-TDK-J330\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TDK-J070\x00\x00', - b'36161-TDK-J080\x00\x00', - b'36161-TDK-J530\x00\x00', - ], - }, - CAR.HONDA_ODYSSEY: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-THR-A010\x00\x00', - b'38897-THR-A020\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THR-A020\x00\x00', - b'39990-THR-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-THR-A010\x00\x00', - b'77959-THR-A110\x00\x00', - b'77959-THR-X010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-THR-A020\x00\x00', - b'36161-THR-A030\x00\x00', - b'36161-THR-A110\x00\x00', - b'36161-THR-A720\x00\x00', - b'36161-THR-A730\x00\x00', - b'36161-THR-A810\x00\x00', - b'36161-THR-A910\x00\x00', - b'36161-THR-C010\x00\x00', - b'36161-THR-D110\x00\x00', - b'36161-THR-K020\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5NZ-A110\x00\x00', - b'28101-5NZ-A310\x00\x00', - b'28101-5NZ-C310\x00\x00', - b'28102-5MX-A001\x00\x00', - b'28102-5MX-A600\x00\x00', - b'28102-5MX-A610\x00\x00', - b'28102-5MX-A700\x00\x00', - b'28102-5MX-A710\x00\x00', - b'28102-5MX-A900\x00\x00', - b'28102-5MX-A910\x00\x00', - b'28102-5MX-C001\x00\x00', - b'28102-5MX-C610\x00\x00', - b'28102-5MX-C910\x00\x00', - b'28102-5MX-D001\x00\x00', - b'28102-5MX-D710\x00\x00', - b'28102-5MX-K610\x00\x00', - b'28103-5NZ-A100\x00\x00', - b'28103-5NZ-A300\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-THR-A040\x00\x00', - b'57114-THR-A110\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-THR-A020\x00\x00', - ], - }, - CAR.HONDA_ODYSSEY_CHN: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6D-H220\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6A-J010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6A-P040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6A-P110\x00\x00', - ], - }, - CAR.HONDA_PILOT: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TG7-A520\x00\x00', - b'54008-TG7-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5EY-A040\x00\x00', - b'28101-5EY-A050\x00\x00', - b'28101-5EY-A100\x00\x00', - b'28101-5EY-A430\x00\x00', - b'28101-5EY-A500\x00\x00', - b'28101-5EZ-A050\x00\x00', - b'28101-5EZ-A060\x00\x00', - b'28101-5EZ-A100\x00\x00', - b'28101-5EZ-A210\x00\x00', - b'28101-5EZ-A330\x00\x00', - b'28101-5EZ-A430\x00\x00', - b'28101-5EZ-A500\x00\x00', - b'28101-5EZ-A600\x00\x00', - b'28101-5EZ-A700\x00\x00', - b'28103-5EY-A110\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TG7-A030\x00\x00', - b'38897-TG7-A040\x00\x00', - b'38897-TG7-A110\x00\x00', - b'38897-TG7-A210\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TG7-A030\x00\x00', - b'39990-TG7-A040\x00\x00', - b'39990-TG7-A060\x00\x00', - b'39990-TG7-A070\x00\x00', - b'39990-TGS-A230\x00\x00', - b'39990-TGS-A320\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TG7-A310\x00\x00', - b'36161-TG7-A520\x00\x00', - b'36161-TG7-A630\x00\x00', - b'36161-TG7-A720\x00\x00', - b'36161-TG7-A820\x00\x00', - b'36161-TG7-A930\x00\x00', - b'36161-TG7-C520\x00\x00', - b'36161-TG7-D520\x00\x00', - b'36161-TG7-D630\x00\x00', - b'36161-TG7-Y630\x00\x00', - b'36161-TG8-A410\x00\x00', - b'36161-TG8-A520\x00\x00', - b'36161-TG8-A630\x00\x00', - b'36161-TG8-A720\x00\x00', - b'36161-TG8-A830\x00\x00', - b'36161-TGS-A030\x00\x00', - b'36161-TGS-A130\x00\x00', - b'36161-TGS-A220\x00\x00', - b'36161-TGS-A320\x00\x00', - b'36161-TGT-A030\x00\x00', - b'36161-TGT-A130\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TG7-A020\x00\x00', - b'77959-TG7-A110\x00\x00', - b'77959-TG7-A210\x00\x00', - b'77959-TG7-Y210\x00\x00', - b'77959-TGS-A010\x00\x00', - b'77959-TGS-A110\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TG7-A130\x00\x00', - b'57114-TG7-A140\x00\x00', - b'57114-TG7-A230\x00\x00', - b'57114-TG7-A240\x00\x00', - b'57114-TG7-A630\x00\x00', - b'57114-TG7-A730\x00\x00', - b'57114-TG8-A140\x00\x00', - b'57114-TG8-A230\x00\x00', - b'57114-TG8-A240\x00\x00', - b'57114-TG8-A630\x00\x00', - b'57114-TG8-A730\x00\x00', - b'57114-TGS-A530\x00\x00', - b'57114-TGT-A530\x00\x00', - ], - }, - CAR.ACURA_RDX: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TX4-A220\x00\x00', - b'57114-TX5-A220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TX4-A030\x00\x00', - b'36161-TX5-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX4-B010\x00\x00', - b'77959-TX4-C010\x00\x00', - b'77959-TX4-C020\x00\x00', - ], - }, - CAR.ACURA_RDX_3G: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TJB-A030\x00\x00', - b'57114-TJB-A040\x00\x00', - b'57114-TJB-A120\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TJB-A040\x00\x00', - b'36802-TJB-A050\x00\x00', - b'36802-TJB-A540\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TJB-A040\x00\x00', - b'36161-TJB-A530\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TJB-A520\x00\x00', - b'54008-TJB-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28102-5YK-A610\x00\x00', - b'28102-5YK-A620\x00\x00', - b'28102-5YK-A630\x00\x00', - b'28102-5YK-A700\x00\x00', - b'28102-5YK-A711\x00\x00', - b'28102-5YK-A800\x00\x00', - b'28102-5YL-A620\x00\x00', - b'28102-5YL-A700\x00\x00', - b'28102-5YL-A711\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TJB-A040\x00\x00', - b'77959-TJB-A120\x00\x00', - b'77959-TJB-A210\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TJB-A040\x00\x00', - b'46114-TJB-A050\x00\x00', - b'46114-TJB-A060\x00\x00', - b'46114-TJB-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TJB-A040\x00\x00', - b'38897-TJB-A110\x00\x00', - b'38897-TJB-A120\x00\x00', - b'38897-TJB-A220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TJB-A030\x00\x00', - b'39990-TJB-A040\x00\x00', - b'39990-TJB-A070\x00\x00', - b'39990-TJB-A130\x00\x00', - ], - }, - CAR.HONDA_RIDGELINE: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6Z-A020\x00\x00', - b'39990-T6Z-A030\x00\x00', - b'39990-T6Z-A050\x00\x00', - b'39990-T6Z-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6Z-A020\x00\x00', - b'36161-T6Z-A310\x00\x00', - b'36161-T6Z-A420\x00\x00', - b'36161-T6Z-A520\x00\x00', - b'36161-T6Z-A620\x00\x00', - b'36161-T6Z-A720\x00\x00', - b'36161-TJZ-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6Z-A010\x00\x00', - b'38897-T6Z-A110\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6Z-A020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T6Z-A120\x00\x00', - b'57114-T6Z-A130\x00\x00', - b'57114-T6Z-A520\x00\x00', - b'57114-T6Z-A610\x00\x00', - b'57114-TJZ-A520\x00\x00', - ], - }, - CAR.HONDA_INSIGHT: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TXM-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TXM-A070\x00\x00', - b'36802-TXM-A080\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TXM-A050\x00\x00', - b'36161-TXM-A060\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TXM-A230\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TXM-A030\x00\x00', - b'57114-TXM-A040\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TWA-A910\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TXM-A020\x00\x00', - ], - }, - CAR.HONDA_HRV: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T7A-A010\x00\x00', - b'38897-T7A-A110\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THX-A020\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T7A-A040\x00\x00', - b'36161-T7A-A140\x00\x00', - b'36161-T7A-A240\x00\x00', - b'36161-T7A-C440\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T7A-A230\x00\x00', - ], - }, - CAR.HONDA_HRV_3G: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-3M0-G110\x00\x00', - b'39990-3W0-A030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-3M0-M110\x00\x00', - b'38897-3W1-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-3M0-K840\x00\x00', - b'77959-3V0-A820\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'8S102-3M6-P030\x00\x00', - b'8S102-3W0-A060\x00\x00', - b'8S102-3W0-AB10\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-3M6-M010\x00\x00', - b'57114-3W0-A040\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6EH-A010\x00\x00', - b'28101-6JC-M310\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-3W0-A020\x00\x00', - ], - }, - CAR.ACURA_ILX: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TX6-A010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TV9-A140\x00\x00', - b'36161-TX6-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX6-A230\x00\x00', - b'77959-TX6-C210\x00\x00', - ], - }, - CAR.HONDA_E: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TYF-N030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TYF-E140\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TYF-E010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TYF-G430\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TYF-E030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TYF-E020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TYF-E030\x00\x00', - ], - }, - CAR.HONDA_CIVIC_2022: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T24-T120\x00\x00', - b'39990-T39-A130\x00\x00', - b'39990-T43-J020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T20-A020\x00\x00', - b'38897-T20-A210\x00\x00', - b'38897-T20-A310\x00\x00', - b'38897-T20-A510\x00\x00', - b'38897-T21-A010\x00\x00', - b'38897-T24-Z120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T20-A970\x00\x00', - b'77959-T20-A980\x00\x00', - b'77959-T20-M820\x00\x00', - b'77959-T47-A940\x00\x00', - b'77959-T47-A950\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T20-A060\x00\x00', - b'36161-T20-A070\x00\x00', - b'36161-T20-A080\x00\x00', - b'36161-T24-T070\x00\x00', - b'36161-T47-A050\x00\x00', - b'36161-T47-A070\x00\x00', - b'8S102-T20-AA10\x00\x00', - b'8S102-T47-AA10\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T20-AB40\x00\x00', - b'57114-T24-TB30\x00\x00', - b'57114-T43-JB30\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-65D-A020\x00\x00', - b'28101-65D-A120\x00\x00', - b'28101-65H-A020\x00\x00', - b'28101-65H-A120\x00\x00', - b'28101-65J-N010\x00\x00', - ], - }, -} diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py deleted file mode 100644 index b350455014d347..00000000000000 --- a/selfdrive/car/honda/hondacan.py +++ /dev/null @@ -1,211 +0,0 @@ -from openpilot.selfdrive.car import CanBusBase -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams - -# CAN bus layout with relay -# 0 = ACC-CAN - radar side -# 1 = F-CAN B - powertrain -# 2 = ACC-CAN - camera side -# 3 = F-CAN A - OBDII port - - -class CanBus(CanBusBase): - def __init__(self, CP=None, fingerprint=None) -> None: - # use fingerprint if specified - super().__init__(CP if fingerprint is None else None, fingerprint) - - if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS): - self._pt, self._radar = self.offset + 1, self.offset - else: - self._pt, self._radar = self.offset, self.offset + 1 - - @property - def pt(self) -> int: - return self._pt - - @property - def radar(self) -> int: - return self._radar - - @property - def camera(self) -> int: - return self.offset + 2 - - -def get_lkas_cmd_bus(CAN, car_fingerprint, radar_disabled=False): - no_radar = car_fingerprint in HONDA_BOSCH_RADARLESS - if radar_disabled or no_radar: - # when radar is disabled, steering commands are sent directly to powertrain bus - return CAN.pt - # normally steering commands are sent to radar, which forwards them to powertrain bus - return 0 - - -def get_cruise_speed_conversion(car_fingerprint: str, is_metric: bool) -> float: - # on certain cars, CRUISE_SPEED changes to imperial with car's unit setting - return CV.MPH_TO_MS if car_fingerprint in HONDA_BOSCH_RADARLESS and not is_metric else CV.KPH_TO_MS - - -def create_brake_command(packer, CAN, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw, car_fingerprint, stock_brake): - # TODO: do we loose pressure if we keep pump off for long? - brakelights = apply_brake > 0 - brake_rq = apply_brake > 0 - pcm_fault_cmd = False - - values = { - "COMPUTER_BRAKE": apply_brake, - "BRAKE_PUMP_REQUEST": pump_on, - "CRUISE_OVERRIDE": pcm_override, - "CRUISE_FAULT_CMD": pcm_fault_cmd, - "CRUISE_CANCEL_CMD": pcm_cancel_cmd, - "COMPUTER_BRAKE_REQUEST": brake_rq, - "SET_ME_1": 1, - "BRAKE_LIGHTS": brakelights, - "CHIME": stock_brake["CHIME"] if fcw else 0, # send the chime for stock fcw - "FCW": fcw << 1, # TODO: Why are there two bits for fcw? - "AEB_REQ_1": 0, - "AEB_REQ_2": 0, - "AEB_STATUS": 0, - } - return packer.make_can_msg("BRAKE_COMMAND", CAN.pt, values) - - -def create_acc_commands(packer, CAN, enabled, active, accel, gas, stopping_counter, car_fingerprint): - commands = [] - min_gas_accel = CarControllerParams.BOSCH_GAS_LOOKUP_BP[0] - - control_on = 5 if enabled else 0 - gas_command = gas if active and accel > min_gas_accel else -30000 - accel_command = accel if active else 0 - braking = 1 if active and accel < min_gas_accel else 0 - standstill = 1 if active and stopping_counter > 0 else 0 - standstill_release = 1 if active and stopping_counter == 0 else 0 - - # common ACC_CONTROL values - acc_control_values = { - 'ACCEL_COMMAND': accel_command, - 'STANDSTILL': standstill, - } - - if car_fingerprint in HONDA_BOSCH_RADARLESS: - acc_control_values.update({ - "CONTROL_ON": enabled, - "IDLESTOP_ALLOW": stopping_counter > 200, # allow idle stop after 4 seconds (50 Hz) - }) - else: - acc_control_values.update({ - # setting CONTROL_ON causes car to set POWERTRAIN_DATA->ACC_STATUS = 1 - "CONTROL_ON": control_on, - "GAS_COMMAND": gas_command, # used for gas - "BRAKE_LIGHTS": braking, - "BRAKE_REQUEST": braking, - "STANDSTILL_RELEASE": standstill_release, - }) - acc_control_on_values = { - "SET_TO_3": 0x03, - "CONTROL_ON": enabled, - "SET_TO_FF": 0xff, - "SET_TO_75": 0x75, - "SET_TO_30": 0x30, - } - commands.append(packer.make_can_msg("ACC_CONTROL_ON", CAN.pt, acc_control_on_values)) - - commands.append(packer.make_can_msg("ACC_CONTROL", CAN.pt, acc_control_values)) - return commands - - -def create_steering_control(packer, CAN, apply_steer, lkas_active, car_fingerprint, radar_disabled): - values = { - "STEER_TORQUE": apply_steer if lkas_active else 0, - "STEER_TORQUE_REQUEST": lkas_active, - } - bus = get_lkas_cmd_bus(CAN, car_fingerprint, radar_disabled) - return packer.make_can_msg("STEERING_CONTROL", bus, values) - - -def create_bosch_supplemental_1(packer, CAN, car_fingerprint): - # non-active params - values = { - "SET_ME_X04": 0x04, - "SET_ME_X80": 0x80, - "SET_ME_X10": 0x10, - } - bus = get_lkas_cmd_bus(CAN, car_fingerprint) - return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values) - - -def create_ui_commands(packer, CAN, CP, enabled, pcm_speed, hud, is_metric, acc_hud, lkas_hud): - commands = [] - radar_disabled = CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl - bus_lkas = get_lkas_cmd_bus(CAN, CP.carFingerprint, radar_disabled) - - if CP.openpilotLongitudinalControl: - acc_hud_values = { - 'CRUISE_SPEED': hud.v_cruise, - 'ENABLE_MINI_CAR': 1 if enabled else 0, - # only moves the lead car without ACC_ON - 'HUD_DISTANCE': (hud.lead_distance_bars + 1) % 4, # wraps to 0 at 4 bars - 'IMPERIAL_UNIT': int(not is_metric), - 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, - 'SET_ME_X01_2': 1, - } - - if CP.carFingerprint in HONDA_BOSCH: - acc_hud_values['ACC_ON'] = int(enabled) - acc_hud_values['FCM_OFF'] = 1 - acc_hud_values['FCM_OFF_2'] = 1 - else: - # Shows the distance bars, TODO: stock camera shows updates temporarily while disabled - acc_hud_values['ACC_ON'] = int(enabled) - acc_hud_values['PCM_SPEED'] = pcm_speed * CV.MS_TO_KPH - acc_hud_values['PCM_GAS'] = hud.pcm_accel - acc_hud_values['SET_ME_X01'] = 1 - acc_hud_values['FCM_OFF'] = acc_hud['FCM_OFF'] - acc_hud_values['FCM_OFF_2'] = acc_hud['FCM_OFF_2'] - acc_hud_values['FCM_PROBLEM'] = acc_hud['FCM_PROBLEM'] - acc_hud_values['ICONS'] = acc_hud['ICONS'] - commands.append(packer.make_can_msg("ACC_HUD", CAN.pt, acc_hud_values)) - - lkas_hud_values = { - 'SET_ME_X41': 0x41, - 'STEERING_REQUIRED': hud.steer_required, - 'SOLID_LANES': hud.lanes_visible, - 'BEEP': 0, - } - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - lkas_hud_values['LANE_LINES'] = 3 - lkas_hud_values['DASHED_LANES'] = hud.lanes_visible - # car likely needs to see LKAS_PROBLEM fall within a specific time frame, so forward from camera - lkas_hud_values['LKAS_PROBLEM'] = lkas_hud['LKAS_PROBLEM'] - - if not (CP.flags & HondaFlags.BOSCH_EXT_HUD): - lkas_hud_values['SET_ME_X48'] = 0x48 - - if CP.flags & HondaFlags.BOSCH_EXT_HUD and not CP.openpilotLongitudinalControl: - commands.append(packer.make_can_msg('LKAS_HUD_A', bus_lkas, lkas_hud_values)) - commands.append(packer.make_can_msg('LKAS_HUD_B', bus_lkas, lkas_hud_values)) - else: - commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values)) - - if radar_disabled: - radar_hud_values = { - 'CMBS_OFF': 0x01, - 'SET_TO_1': 0x01, - } - commands.append(packer.make_can_msg('RADAR_HUD', CAN.pt, radar_hud_values)) - - if CP.carFingerprint == CAR.HONDA_CIVIC_BOSCH: - commands.append(packer.make_can_msg("LEGACY_BRAKE_COMMAND", CAN.pt, {})) - - return commands - - -def spam_buttons_command(packer, CAN, button_val, car_fingerprint): - values = { - 'CRUISE_BUTTONS': button_val, - 'CRUISE_SETTING': 0, - } - # send buttons to camera on radarless cars - bus = CAN.camera if car_fingerprint in HONDA_BOSCH_RADARLESS else CAN.pt - return packer.make_can_msg("SCM_BUTTONS", bus, values) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py deleted file mode 100755 index ae19f6940f4ef7..00000000000000 --- a/selfdrive/car/honda/interface.py +++ /dev/null @@ -1,255 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.helpers import interp -from openpilot.selfdrive.car.honda.hondacan import CanBus -from openpilot.selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CruiseSettings, HondaFlags, CAR, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.disable_ecu import disable_ecu - - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -TransmissionType = car.CarParams.TransmissionType -BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, - CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} -SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.altButton1} - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - if CP.carFingerprint in HONDA_BOSCH: - return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX - else: - # NIDECs don't allow acceleration near cruise_speed, - # so limit limits of pid to prevent windup - ACCEL_MAX_VALS = [CarControllerParams.NIDEC_ACCEL_MAX, 0.2] - ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .2] - return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "honda" - - CAN = CanBus(ret, fingerprint) - - if candidate in HONDA_BOSCH: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaBosch)] - ret.radarUnavailable = True - # Disable the radar and let openpilot control longitudinal - # WARNING: THIS DISABLES AEB! - # If Bosch radarless, this blocks ACC messages from the camera - ret.experimentalLongitudinalAvailable = True - ret.openpilotLongitudinalControl = experimental_long - ret.pcmCruise = not ret.openpilotLongitudinalControl - else: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaNidec)] - ret.openpilotLongitudinalControl = True - - ret.pcmCruise = True - - if candidate == CAR.HONDA_CRV_5G: - ret.enableBsm = 0x12f8bfa7 in fingerprint[CAN.radar] - - # Detect Bosch cars with new HUD msgs - if any(0x33DA in f for f in fingerprint.values()): - ret.flags |= HondaFlags.BOSCH_EXT_HUD.value - - # Accord ICE 1.5T CVT has different gearbox message - if candidate == CAR.HONDA_ACCORD and 0x191 in fingerprint[CAN.pt]: - ret.transmissionType = TransmissionType.cvt - - # Certain Hondas have an extra steering sensor at the bottom of the steering rack, - # which improves controls quality as it removes the steering column torsion from feedback. - # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. - # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0], [0]] - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward - - if candidate in HONDA_BOSCH: - ret.longitudinalActuatorDelay = 0.5 # s - if candidate in HONDA_BOSCH_RADARLESS: - ret.stopAccel = CarControllerParams.BOSCH_ACCEL_MIN # stock uses -4.0 m/s^2 once stopped but limited by safety model - else: - # default longitudinal tuning for all hondas - ret.longitudinalTuning.kiBP = [0., 5., 35.] - ret.longitudinalTuning.kiV = [1.2, 0.8, 0.5] - - eps_modified = False - for fw in car_fw: - if fw.ecu == "eps" and b"," in fw.fwVersion: - eps_modified = True - - if candidate == CAR.HONDA_CIVIC: - if eps_modified: - # stock request input values: 0x0000, 0x00DE, 0x014D, 0x01EF, 0x0290, 0x0377, 0x0454, 0x0610, 0x06EE - # stock request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x1680, 0x1680 - # modified request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x2880, 0x3180 - # stock filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108 - # modified filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0400, 0x0480 - # note: max request allowed is 4096, but request is capped at 3840 in firmware, so modifications result in 2x max - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] - - elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CIVIC_2022): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate == CAR.HONDA_ACCORD: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - - if eps_modified: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] - else: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - - elif candidate == CAR.ACURA_ILX: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate in (CAR.HONDA_CRV, CAR.HONDA_CRV_EU): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_CRV_5G: - if eps_modified: - # stock request input values: 0x0000, 0x00DB, 0x01BB, 0x0296, 0x0377, 0x0454, 0x0532, 0x0610, 0x067F - # stock request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x129A, 0x134D, 0x1400 - # modified request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x1ACD, 0x239A, 0x2800 - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_CRV_HYBRID: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_FIT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - - elif candidate == CAR.HONDA_FREED: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - - elif candidate in (CAR.HONDA_HRV, CAR.HONDA_HRV_3G): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - if candidate == CAR.HONDA_HRV: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] - ret.wheelSpeedFactor = 1.025 - else: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] # TODO: can probably use some tuning - - elif candidate == CAR.ACURA_RDX: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate == CAR.ACURA_RDX_3G: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] - - elif candidate in (CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN): - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - if candidate == CAR.HONDA_ODYSSEY_CHN: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - - elif candidate == CAR.HONDA_PILOT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.HONDA_RIDGELINE: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.HONDA_INSIGHT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - - elif candidate == CAR.HONDA_E: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning - - else: - raise ValueError(f"unsupported car {candidate}") - - # These cars use alternate user brake msg (0x1BE) - # TODO: Only detect feature for Accord/Accord Hybrid, not all Bosch DBCs have BRAKE_MODULE - if 0x1BE in fingerprint[CAN.pt] and candidate in (CAR.HONDA_ACCORD, CAR.HONDA_HRV_3G): - ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value - - if ret.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE - - # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) - if candidate in HONDA_NIDEC_ALT_SCM_MESSAGES: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_NIDEC_ALT - - if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG - - if candidate in HONDA_BOSCH_RADARLESS: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS - - # min speed to enable ACC. if car can do stop and go, then set enabling speed - # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not - # conflict with PCM acc - ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.HONDA_CIVIC}) - ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.51 * CV.MPH_TO_MS - - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.8 - - return ret - - @staticmethod - def init(CP, can_recv, can_send): - if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl: - disable_ecu(can_recv, can_send, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03') - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - - ret.buttonEvents = [ - *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT), - *create_button_events(self.CS.cruise_setting, self.CS.prev_cruise_setting, SETTINGS_BUTTONS_DICT), - ] - - # events - events = self.create_common_events(ret, pcm_enable=False) - if self.CP.pcmCruise and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.belowEngageSpeed) - - if self.CP.pcmCruise: - # we engage when pcm is active (rising edge) - if ret.cruiseState.enabled and not self.CS.out.cruiseState.enabled: - events.add(EventName.pcmEnable) - elif not ret.cruiseState.enabled and (c.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): - # it can happen that car cruise disables while comma system is enabled: need to - # keep braking if needed or if the speed is very low - if ret.vEgo < self.CP.minEnableSpeed + 2.: - # non loud alert if cruise disables below 25mph as expected (+ a little margin) - events.add(EventName.speedTooLow) - else: - events.add(EventName.cruiseDisabled) - if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: - events.add(EventName.manualRestart) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py deleted file mode 100755 index 8090f8e03e7735..00000000000000 --- a/selfdrive/car/honda/radar_interface.py +++ /dev/null @@ -1,84 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.honda.values import DBC - - -def _create_nidec_can_parser(car_fingerprint): - radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) - messages = [(m, 20) for m in radar_messages] - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.track_id = 0 - self.radar_fault = False - self.radar_wrong_config = False - self.radar_off_can = CP.radarUnavailable - self.radar_ts = CP.radarTimeStep - - self.delay = int(round(0.1 / CP.radarTimeStep)) # 0.1s delay of radar - - # Nidec - if self.radar_off_can: - self.rcp = None - else: - self.rcp = _create_nidec_can_parser(CP.carFingerprint) - self.trigger_msg = 0x445 - self.updated_messages = set() - - def update(self, can_strings): - # in Bosch radar and we are only steering for now, so sleep 0.05s to keep - # radard at 20Hz and return no points - if self.radar_off_can: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - - for ii in sorted(updated_messages): - cpt = self.rcp.vl[ii] - if ii == 0x400: - # check for radar faults - self.radar_fault = cpt['RADAR_STATE'] != 0x79 - self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 - elif cpt['LONG_DIST'] < 255: - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] - - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - if self.radar_fault: - errors.append("fault") - if self.radar_wrong_config: - errors.append("wrongConfig") - ret.errors = errors - - ret.points = list(self.pts.values()) - - return ret diff --git a/selfdrive/car/honda/tests/__init__.py b/selfdrive/car/honda/tests/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/honda/tests/test_honda.py b/selfdrive/car/honda/tests/test_honda.py deleted file mode 100644 index b8ad7872b29fa3..00000000000000 --- a/selfdrive/car/honda/tests/test_honda.py +++ /dev/null @@ -1,14 +0,0 @@ -import re - -from openpilot.selfdrive.car.honda.fingerprints import FW_VERSIONS - -HONDA_FW_VERSION_RE = br"[A-Z0-9]{5}-[A-Z0-9]{3}(-|,)[A-Z0-9]{4}(\x00){2}$" - - -class TestHondaFingerprint: - def test_fw_version_format(self): - # Asserts all FW versions follow an expected format - for fw_by_ecu in FW_VERSIONS.values(): - for fws in fw_by_ecu.values(): - for fw in fws: - assert re.match(HONDA_FW_VERSION_RE, fw) is not None, fw diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py deleted file mode 100644 index 53e5435f294c45..00000000000000 --- a/selfdrive/car/honda/values.py +++ /dev/null @@ -1,331 +0,0 @@ -from dataclasses import dataclass -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarControllerParams: - # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we - # perform the closed loop control, and might need some - # to apply some more braking if we're on a downhill slope. - # Our controller should still keep the 2 second average above - # -3.5 m/s^2 as per planner limits - NIDEC_ACCEL_MIN = -4.0 # m/s^2 - NIDEC_ACCEL_MAX = 1.6 # m/s^2, lower than 2.0 m/s^2 for tuning reasons - - NIDEC_ACCEL_LOOKUP_BP = [-1., 0., .6] - NIDEC_ACCEL_LOOKUP_V = [-4.8, 0., 2.0] - - NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6] - NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.] - - NIDEC_GAS_MAX = 198 # 0xc6 - NIDEC_BRAKE_MAX = 1024 // 4 - - BOSCH_ACCEL_MIN = -3.5 # m/s^2 - BOSCH_ACCEL_MAX = 2.0 # m/s^2 - - BOSCH_GAS_LOOKUP_BP = [-0.2, 2.0] # 2m/s^2 - BOSCH_GAS_LOOKUP_V = [0, 1600] - - def __init__(self, CP): - self.STEER_MAX = CP.lateralParams.torqueBP[-1] - # mirror of list (assuming first item is zero) for interp of signed request values - assert(CP.lateralParams.torqueBP[0] == 0) - assert(CP.lateralParams.torqueBP[0] == 0) - self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) - self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) - - -class HondaFlags(IntFlag): - # Detected flags - # Bosch models with alternate set of LKAS_HUD messages - BOSCH_EXT_HUD = 1 - BOSCH_ALT_BRAKE = 2 - - # Static flags - BOSCH = 4 - BOSCH_RADARLESS = 8 - - NIDEC = 16 - NIDEC_ALT_PCM_ACCEL = 32 - NIDEC_ALT_SCM_MESSAGES = 64 - - -# Car button codes -class CruiseButtons: - RES_ACCEL = 4 - DECEL_SET = 3 - CANCEL = 2 - MAIN = 1 - - -class CruiseSettings: - DISTANCE = 3 - LKAS = 1 - - -# See dbc files for info on values -VISUAL_HUD = { - VisualAlert.none: 0, - VisualAlert.fcw: 1, - VisualAlert.steerRequired: 1, - VisualAlert.ldw: 1, - VisualAlert.brakePressed: 10, - VisualAlert.wrongGear: 6, - VisualAlert.seatbeltUnbuckled: 5, - VisualAlert.speedTooHigh: 8 -} - - -@dataclass -class HondaCarDocs(CarDocs): - package: str = "Honda Sensing" - - def init_make(self, CP: car.CarParams): - if CP.flags & HondaFlags.BOSCH: - self.car_parts = CarParts.common([CarHarness.bosch_b]) if CP.flags & HondaFlags.BOSCH_RADARLESS else CarParts.common([CarHarness.bosch_a]) - else: - self.car_parts = CarParts.common([CarHarness.nidec]) - - -class Footnote(Enum): - CIVIC_DIESEL = CarFootnote( - "2019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.", - Column.FSR_STEERING) - - -class HondaBoschPlatformConfig(PlatformConfig): - def init(self): - self.flags |= HondaFlags.BOSCH - - -class HondaNidecPlatformConfig(PlatformConfig): - def init(self): - self.flags |= HondaFlags.NIDEC - - -class CAR(Platforms): - # Bosch Cars - HONDA_ACCORD = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarDocs("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarDocs("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), - ], - # steerRatio: 11.82 is spec end-to-end - CarSpecs(mass=3279 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=16.33, centerToFrontRatio=0.39, tireStiffnessFactor=0.8467), - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_CIVIC_BOSCH = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", - footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), - HondaCarDocs("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), - ], - CarSpecs(mass=1326, wheelbase=2.7, steerRatio=15.38, centerToFrontRatio=0.4), # steerRatio: 10.93 is end-to-end spec - dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), - ) - HONDA_CIVIC_BOSCH_DIESEL = HondaBoschPlatformConfig( - [], # don't show in docs - HONDA_CIVIC_BOSCH.specs, - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_CIVIC_2022 = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Civic 2022-24", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - HondaCarDocs("Honda Civic Hatchback 2022-24", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - ], - HONDA_CIVIC_BOSCH.specs, - dbc_dict('honda_civic_ex_2022_can_generated', None), - flags=HondaFlags.BOSCH_RADARLESS, - ) - HONDA_CRV_5G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], - # steerRatio: 12.3 is spec end-to-end - CarSpecs(mass=3410 * CV.LB_TO_KG, wheelbase=2.66, steerRatio=16.0, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), - dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), - flags=HondaFlags.BOSCH_ALT_BRAKE, - ) - HONDA_CRV_HYBRID = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V Hybrid 2017-21", min_steer_speed=12. * CV.MPH_TO_MS)], - # mass: mean of 4 models in kg, steerRatio: 12.3 is spec end-to-end - CarSpecs(mass=1667, wheelbase=2.66, steerRatio=16, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_HRV_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda HR-V 2023", "All")], - CarSpecs(mass=3125 * CV.LB_TO_KG, wheelbase=2.61, steerRatio=15.2, centerToFrontRatio=0.41, tireStiffnessFactor=0.5), - dbc_dict('honda_civic_ex_2022_can_generated', None), - flags=HondaFlags.BOSCH_RADARLESS, - ) - ACURA_RDX_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=4068 * CV.LB_TO_KG, wheelbase=2.75, steerRatio=11.95, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), # as spec - dbc_dict('acura_rdx_2020_can_generated', None), - flags=HondaFlags.BOSCH_ALT_BRAKE, - ) - HONDA_INSIGHT = HondaBoschPlatformConfig( - [HondaCarDocs("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=2987 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.0, centerToFrontRatio=0.39, tireStiffnessFactor=0.82), # as spec - dbc_dict('honda_insight_ex_2019_can_generated', None), - ) - HONDA_E = HondaBoschPlatformConfig( - [HondaCarDocs("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=3338.8 * CV.LB_TO_KG, wheelbase=2.5, centerToFrontRatio=0.5, steerRatio=16.71, tireStiffnessFactor=0.82), - dbc_dict('acura_rdx_2020_can_generated', None), - ) - - # Nidec Cars - ACURA_ILX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS)], - CarSpecs(mass=3095 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=18.61, centerToFrontRatio=0.37, tireStiffnessFactor=0.72), # 15.3 is spec end-to-end - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CRV = HondaNidecPlatformConfig( - [HondaCarDocs("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3572 * CV.LB_TO_KG, wheelbase=2.62, steerRatio=16.89, centerToFrontRatio=0.41, tireStiffnessFactor=0.444), # as spec - dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CRV_EU = HondaNidecPlatformConfig( - [], # Euro version of CRV Touring, don't show in docs - HONDA_CRV.specs, - dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_FIT = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=2644 * CV.LB_TO_KG, wheelbase=2.53, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_FREED = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3086. * CV.LB_TO_KG, wheelbase=2.74, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), # mostly copied from FIT - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_HRV = HondaNidecPlatformConfig( - [HondaCarDocs("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS)], - HONDA_HRV_3G.specs, - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_ODYSSEY = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Odyssey 2018-20")], - CarSpecs(mass=1900, wheelbase=3.0, steerRatio=14.35, centerToFrontRatio=0.41, tireStiffnessFactor=0.82), - dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_PCM_ACCEL, - ) - HONDA_ODYSSEY_CHN = HondaNidecPlatformConfig( - [], # Chinese version of Odyssey, don't show in docs - HONDA_ODYSSEY.specs, - dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - ACURA_RDX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3925 * CV.LB_TO_KG, wheelbase=2.68, steerRatio=15.0, centerToFrontRatio=0.38, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_PILOT = HondaNidecPlatformConfig( - [ - HondaCarDocs("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), - HondaCarDocs("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), - ], - CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_RIDGELINE = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Ridgeline 2017-24", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=4515 * CV.LB_TO_KG, wheelbase=3.18, centerToFrontRatio=0.41, steerRatio=15.59, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CIVIC = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE")], - CarSpecs(mass=1326, wheelbase=2.70, centerToFrontRatio=0.4, steerRatio=15.38), # 10.93 is end-to-end spec - dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - ) - - -HONDA_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xF112) -HONDA_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xF112) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # Currently used to fingerprint - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=1, - ), - - # Data collection requests: - # Log manufacturer-specific identifier for current ECUs - Request( - [HONDA_ALT_VERSION_REQUEST], - [HONDA_ALT_VERSION_RESPONSE], - bus=1, - logging=True, - ), - # Nidec PT bus - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=0, - ), - # Bosch PT bus - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=1, - obd_multiplexing=False, - ), - ], - # We lose these ECUs without the comma power on these cars. - # Note that we still attempt to match with them when they are present - # This is or'd with (ALL_ECUS - ESSENTIAL_ECUS) from fw_versions.py - non_essential_ecus={ - Ecu.eps: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_2022, CAR.HONDA_E, CAR.HONDA_HRV_3G], - Ecu.vsa: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_2022, CAR.HONDA_CRV_5G, CAR.HONDA_CRV_HYBRID, - CAR.HONDA_E, CAR.HONDA_HRV_3G, CAR.HONDA_INSIGHT], - }, - extra_ecus=[ - (Ecu.combinationMeter, 0x18da60f1, None), - (Ecu.programmedFuelInjection, 0x18da10f1, None), - # The only other ECU on PT bus accessible by camera on radarless Civic - # This is likely a manufacturer-specific sub-address implementation: the camera responds to this and 0x18dab0f1 - # Unclear what the part number refers to: 8S103 is 'Camera Set Mono', while 36160 is 'Camera Monocular - Honda' - # TODO: add query back, camera does not support querying both in parallel and 0x18dab0f1 often fails to respond - # (Ecu.unknown, 0x18DAB3F1, None), - ], -) - -STEER_THRESHOLD = { - # default is 1200, overrides go here - CAR.ACURA_RDX: 400, - CAR.HONDA_CRV_EU: 400, -} - -HONDA_NIDEC_ALT_PCM_ACCEL = CAR.with_flags(HondaFlags.NIDEC_ALT_PCM_ACCEL) -HONDA_NIDEC_ALT_SCM_MESSAGES = CAR.with_flags(HondaFlags.NIDEC_ALT_SCM_MESSAGES) -HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) -HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) - - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/hyundai/__init__.py b/selfdrive/car/hyundai/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py deleted file mode 100644 index 0e3a3f0afd2dfd..00000000000000 --- a/selfdrive/car/hyundai/carcontroller.py +++ /dev/null @@ -1,206 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import DT_CTRL, apply_driver_steer_torque_limits, common_fault_avoidance, make_tester_present_msg -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.helpers import clip -from openpilot.selfdrive.car.hyundai import hyundaicanfd, hyundaican -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - -# EPS faults if you apply torque while the steering angle is above 90 degrees for more than 1 second -# All slightly below EPS thresholds to avoid fault -MAX_ANGLE = 85 -MAX_ANGLE_FRAMES = 89 -MAX_ANGLE_CONSECUTIVE_FRAMES = 2 - - -def process_hud_alert(enabled, fingerprint, hud_control): - sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) - - # initialize to no line visible - # TODO: this is not accurate for all cars - sys_state = 1 - if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active - sys_state = 3 if enabled or sys_warning else 4 - elif hud_control.leftLaneVisible: - sys_state = 5 - elif hud_control.rightLaneVisible: - sys_state = 6 - - # initialize to no warnings - left_lane_warning = 0 - right_lane_warning = 0 - if hud_control.leftLaneDepart: - left_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 - if hud_control.rightLaneDepart: - right_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 - - return sys_warning, sys_state, left_lane_warning, right_lane_warning - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.CAN = CanBus(CP) - self.params = CarControllerParams(CP) - self.packer = CANPacker(dbc_name) - self.angle_limit_counter = 0 - - self.accel_last = 0 - self.apply_steer_last = 0 - self.car_fingerprint = CP.carFingerprint - self.last_button_frame = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - - # steering torque - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) - - # >90 degree steering fault prevention - self.angle_limit_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringAngleDeg) >= MAX_ANGLE, CC.latActive, - self.angle_limit_counter, MAX_ANGLE_FRAMES, - MAX_ANGLE_CONSECUTIVE_FRAMES) - - if not CC.latActive: - apply_steer = 0 - - # Hold torque with induced temporary fault when cutting the actuation bit - torque_fault = CC.latActive and not apply_steer_req - - self.apply_steer_last = apply_steer - - # accel + longitudinal - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - stopping = actuators.longControlState == LongCtrlState.stopping - set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_KPH if CS.is_metric else CV.MS_TO_MPH) - - # HUD messages - sys_warning, sys_state, left_lane_warning, right_lane_warning = process_hud_alert(CC.enabled, self.car_fingerprint, - hud_control) - - can_sends = [] - - # *** common hyundai stuff *** - - # tester present - w/ no response (keeps relevant ECU disabled) - if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl: - # for longitudinal control, either radar or ADAS driving ECU - addr, bus = 0x7d0, 0 - if self.CP.flags & HyundaiFlags.CANFD_HDA2.value: - addr, bus = 0x730, self.CAN.ECAN - can_sends.append(make_tester_present_msg(addr, bus, suppress_response=True)) - - # for blinkers - if self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: - can_sends.append(make_tester_present_msg(0x7b1, self.CAN.ECAN, suppress_response=True)) - - # CAN-FD platforms - if self.CP.carFingerprint in CANFD_CAR: - hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 - hda2_long = hda2 and self.CP.openpilotLongitudinalControl - - # steering control - can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer)) - - # prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU - if self.frame % 5 == 0 and hda2: - can_sends.append(hyundaicanfd.create_suppress_lfa(self.packer, self.CAN, CS.hda2_lfa_block_msg, - self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING)) - - # LFA and HDA icons - if self.frame % 5 == 0 and (not hda2 or hda2_long): - can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.enabled)) - - # blinkers - if hda2 and self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: - can_sends.extend(hyundaicanfd.create_spas_messages(self.packer, self.CAN, self.frame, CC.leftBlinker, CC.rightBlinker)) - - if self.CP.openpilotLongitudinalControl: - if hda2: - can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.CAN, self.frame)) - if self.frame % 2 == 0: - can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CAN, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override, - set_speed_in_units, hud_control)) - self.accel_last = accel - else: - # button presses - can_sends.extend(self.create_button_messages(CC, CS, use_clu11=False)) - else: - can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.CP, apply_steer, apply_steer_req, - torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - left_lane_warning, right_lane_warning)) - - if not self.CP.openpilotLongitudinalControl: - can_sends.extend(self.create_button_messages(CC, CS, use_clu11=True)) - - if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: - # TODO: unclear if this is needed - jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 - use_fca = self.CP.flags & HyundaiFlags.USE_FCA.value - can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), - hud_control, set_speed_in_units, stopping, - CC.cruiseControl.override, use_fca)) - - # 20 Hz LFA MFA message - if self.frame % 5 == 0 and self.CP.flags & HyundaiFlags.SEND_LFA.value: - can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled)) - - # 5 Hz ACC options - if self.frame % 20 == 0 and self.CP.openpilotLongitudinalControl: - can_sends.extend(hyundaican.create_acc_opt(self.packer)) - - # 2 Hz front radar options - if self.frame % 50 == 0 and self.CP.openpilotLongitudinalControl: - can_sends.append(hyundaican.create_frt_radar_opt(self.packer)) - - new_actuators = actuators.as_builder() - new_actuators.steer = apply_steer / self.params.STEER_MAX - new_actuators.steerOutputCan = apply_steer - new_actuators.accel = accel - - self.frame += 1 - return new_actuators, can_sends - - def create_button_messages(self, CC: car.CarControl, CS: car.CarState, use_clu11: bool): - can_sends = [] - if use_clu11: - if CC.cruiseControl.cancel: - can_sends.append(hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.CANCEL, self.CP)) - elif CC.cruiseControl.resume: - # send resume at a max freq of 10Hz - if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: - # send 25 messages at a time to increases the likelihood of resume being accepted - can_sends.extend([hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.RES_ACCEL, self.CP)] * 25) - if (self.frame - self.last_button_frame) * DT_CTRL >= 0.15: - self.last_button_frame = self.frame - else: - if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: - # cruise cancel - if CC.cruiseControl.cancel: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, self.CAN, CS.cruise_info)) - self.last_button_frame = self.frame - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.CANCEL)) - self.last_button_frame = self.frame - - # cruise standstill resume - elif CC.cruiseControl.resume: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - # TODO: resume for alt button cars - pass - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.RES_ACCEL)) - self.last_button_frame = self.frame - - return can_sends diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py deleted file mode 100644 index 1b56b3304ebab1..00000000000000 --- a/selfdrive/car/hyundai/carstate.py +++ /dev/null @@ -1,369 +0,0 @@ -from collections import deque -import copy -import math - -from cereal import car -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, \ - CANFD_CAR, Buttons, CarControllerParams -from openpilot.selfdrive.car.interfaces import CarStateBase - -PREV_BUTTON_SAMPLES = 8 -CLUSTER_SAMPLE_RATE = 20 # frames -STANDSTILL_THRESHOLD = 12 * 0.03125 * CV.KPH_TO_MS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.cruise_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - - self.gear_msg_canfd = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ - "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ - "GEAR_SHIFTER" - if CP.carFingerprint in CANFD_CAR: - self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] - elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] - else: # preferred and elect gear methods use same definition - self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] - - self.accelerator_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ - "ACCELERATOR_ALT" if CP.flags & HyundaiFlags.HYBRID else \ - "ACCELERATOR_BRAKE_ALT" - self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ - "CRUISE_BUTTONS" - self.is_metric = False - self.buttons_counter = 0 - - self.cruise_info = {} - - # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz - self.cluster_speed = 0 - self.cluster_speed_counter = CLUSTER_SAMPLE_RATE - - self.params = CarControllerParams(CP) - - def update(self, cp, cp_cam): - if self.CP.carFingerprint in CANFD_CAR: - return self.update_canfd(cp, cp_cam) - - ret = car.CarState.new_message() - cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp - self.is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 - speed_conv = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - - ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], - cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) - - ret.seatbeltUnlatched = cp.vl["CGW1"]["CF_Gway_DrvSeatBeltSw"] == 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHL_SPD11"]["WHL_SPD_FL"], - cp.vl["WHL_SPD11"]["WHL_SPD_FR"], - cp.vl["WHL_SPD11"]["WHL_SPD_RL"], - cp.vl["WHL_SPD11"]["WHL_SPD_RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - self.cluster_speed_counter += 1 - if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE: - self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"] - self.cluster_speed_counter = 0 - - # Mimic how dash converts to imperial. - # Sorento is the only platform where CF_Clu_VehicleSpeed is already imperial when not is_metric - # TODO: CGW_USM1->CF_Gway_DrLockSoundRValue may describe this - if not self.is_metric and self.CP.carFingerprint not in (CAR.KIA_SORENTO,): - self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) - - ret.vEgoCluster = self.cluster_speed * speed_conv - - ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] - ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] - ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( - 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) - ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] - ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) - ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 - - # cruise state - if self.CP.openpilotLongitudinalControl: - # These are not used for engage/disengage since openpilot keeps track of state using the buttons - ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0 - ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = False - ret.cruiseState.nonAdaptive = False - else: - ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1 - ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0 - ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4. - ret.cruiseState.nonAdaptive = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 2. # Shows 'Cruise Control' on dash - ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv - - # TODO: Find brake pressure - ret.brake = 0 - ret.brakePressed = cp.vl["TCS13"]["DriverOverride"] == 2 # 2 includes regen braking by user on HEV/EV - ret.brakeHoldActive = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY - ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 - ret.espDisabled = cp.vl["TCS11"]["TCS_PAS"] == 1 - ret.espActive = cp.vl["TCS11"]["ABS_ACT"] == 1 - ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - - if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - if self.CP.flags & HyundaiFlags.HYBRID: - ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. - else: - ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. - ret.gasPressed = ret.gas > 0 - else: - ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100. - ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) - - # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, - # as this seems to be standard over all cars, but is not the preferred method. - if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] - elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - gear = cp.vl["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - gear = cp.vl["TCU12"]["CUR_GR"] - else: - gear = cp.vl["LVR12"]["CF_Lvr_Gear"] - - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) - - if not self.CP.openpilotLongitudinalControl: - aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12" - aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct" - aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 - scc_warning = cp_cruise.vl["SCC12"]["TakeOverReq"] == 1 # sometimes only SCC system shows an FCW - aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 - ret.stockFcw = (aeb_warning or scc_warning) and not aeb_braking - ret.stockAeb = aeb_warning and aeb_braking - - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 - ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 - - # save the entire LKAS11 and CLU11 - self.lkas11 = copy.copy(cp_cam.vl["LKAS11"]) - self.clu11 = copy.copy(cp.vl["CLU11"]) - self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE - self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwState"]) - self.main_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwMain"]) - - return ret - - def update_canfd(self, cp, cp_cam): - ret = car.CarState.new_message() - - self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1 - speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - - if self.CP.flags & (HyundaiFlags.EV | HyundaiFlags.HYBRID): - offset = 255. if self.CP.flags & HyundaiFlags.EV else 1023. - ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset - ret.gasPressed = ret.gas > 1e-5 - else: - ret.gasPressed = bool(cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL_PRESSED"]) - - ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1 - - ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR"] == 1 - ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT"] == 0 - - gear = cp.vl[self.gear_msg_canfd]["GEAR"] - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) - - # TODO: figure out positions - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_1"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_2"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_3"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_4"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEERING_RATE"] - ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEERING_ANGLE"] * -1 - ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] - ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) - ret.steerFaultTemporary = cp.vl["MDPS"]["LKA_FAULT"] != 0 - - # TODO: alt signal usage may be described by cp.vl['BLINKERS']['USE_ALT_LAMP'] - left_blinker_sig, right_blinker_sig = "LEFT_LAMP", "RIGHT_LAMP" - if self.CP.carFingerprint == CAR.HYUNDAI_KONA_EV_2ND_GEN: - left_blinker_sig, right_blinker_sig = "LEFT_LAMP_ALT", "RIGHT_LAMP_ALT" - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"][left_blinker_sig], - cp.vl["BLINKERS"][right_blinker_sig]) - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 - ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 - - # cruise state - # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement - ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0 - if self.CP.openpilotLongitudinalControl: - # These are not used for engage/disengage since openpilot keeps track of state using the buttons - ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = False - else: - cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp - ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2) - ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1 - ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor - self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) - - # Manual Speed Limit Assist is a feature that replaces non-adaptive cruise control on EV CAN FD platforms. - # It limits the vehicle speed, overridable by pressing the accelerator past a certain point. - # The car will brake, but does not respect positive acceleration commands in this mode - # TODO: find this message on ICE & HYBRID cars + cruise control signals (if exists) - if self.CP.flags & HyundaiFlags.EV: - ret.cruiseState.nonAdaptive = cp.vl["MANUAL_SPEED_LIMIT_ASSIST"]["MSLA_ENABLED"] == 1 - - self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["CRUISE_BUTTONS"]) - self.main_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["ADAPTIVE_CRUISE_MAIN_BTN"]) - self.buttons_counter = cp.vl[self.cruise_btns_msg_canfd]["COUNTER"] - ret.accFaulted = cp.vl["TCS"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - - if self.CP.flags & HyundaiFlags.CANFD_HDA2: - self.hda2_lfa_block_msg = copy.copy(cp_cam.vl["CAM_0x362"] if self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING - else cp_cam.vl["CAM_0x2a4"]) - - return ret - - def get_can_parser(self, CP): - if CP.carFingerprint in CANFD_CAR: - return self.get_can_parser_canfd(CP) - - messages = [ - # address, frequency - ("MDPS12", 50), - ("TCS11", 100), - ("TCS13", 50), - ("TCS15", 10), - ("CLU11", 50), - ("CLU15", 5), - ("ESP12", 100), - ("CGW1", 10), - ("CGW2", 5), - ("CGW4", 5), - ("WHL_SPD11", 50), - ("SAS11", 100), - ] - - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in CAMERA_SCC_CAR: - messages += [ - ("SCC11", 50), - ("SCC12", 50), - ] - if CP.flags & HyundaiFlags.USE_FCA.value: - messages.append(("FCA11", 50)) - - if CP.enableBsm: - messages.append(("LCA11", 50)) - - if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - messages.append(("E_EMS11", 50)) - else: - messages += [ - ("EMS12", 100), - ("EMS16", 100), - ] - - if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - messages.append(("ELECT_GEAR", 20)) - elif CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - pass - elif CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - messages.append(("TCU12", 100)) - else: - messages.append(("LVR12", 100)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - if CP.carFingerprint in CANFD_CAR: - return CarState.get_cam_can_parser_canfd(CP) - - messages = [ - ("LKAS11", 100) - ] - - if not CP.openpilotLongitudinalControl and CP.carFingerprint in CAMERA_SCC_CAR: - messages += [ - ("SCC11", 50), - ("SCC12", 50), - ] - - if CP.flags & HyundaiFlags.USE_FCA.value: - messages.append(("FCA11", 50)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - - def get_can_parser_canfd(self, CP): - messages = [ - (self.gear_msg_canfd, 100), - (self.accelerator_msg_canfd, 100), - ("WHEEL_SPEEDS", 100), - ("STEERING_SENSORS", 100), - ("MDPS", 100), - ("TCS", 50), - ("CRUISE_BUTTONS_ALT", 50), - ("BLINKERS", 4), - ("DOORS_SEATBELTS", 4), - ] - - if CP.flags & HyundaiFlags.EV: - messages += [ - ("MANUAL_SPEED_LIMIT_ASSIST", 10), - ] - - if not (CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): - messages += [ - ("CRUISE_BUTTONS", 50) - ] - - if CP.enableBsm: - messages += [ - ("BLINDSPOTS_REAR_CORNERS", 20), - ] - - if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl: - messages += [ - ("SCC_CONTROL", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).ECAN) - - @staticmethod - def get_cam_can_parser_canfd(CP): - messages = [] - if CP.flags & HyundaiFlags.CANFD_HDA2: - block_lfa_msg = "CAM_0x362" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "CAM_0x2a4" - messages += [(block_lfa_msg, 20)] - elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC: - messages += [ - ("SCC_CONTROL", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).CAM) diff --git a/selfdrive/car/hyundai/fingerprints.py b/selfdrive/car/hyundai/fingerprints.py deleted file mode 100644 index 6c7480a15d0b13..00000000000000 --- a/selfdrive/car/hyundai/fingerprints.py +++ /dev/null @@ -1,1141 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.hyundai.values import CAR - -Ecu = car.CarParams.Ecu - -# The existence of SCC or RDR in the fwdRadar FW usually determines the radar's function, -# i.e. if it sends the SCC messages or if another ECU like the camera or ADAS Driving ECU does - - -FW_VERSIONS = { - CAR.HYUNDAI_AZERA_6TH_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', - ], - }, - CAR.HYUNDAI_AZERA_HEV_6TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.00 99211-G8000 180903', - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.01 99211-G8000 181109', - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', - b'\xf1\x00IG MDPS C 1.00 1.01 56310M9350\x00 4IH8C101', - b'\xf1\x00IG MDPS C 1.00 1.02 56310M9350\x00 4IH8C102', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', - b'\xf1\x00IGhe SCC FHCUP 1.00 1.01 99110-M9000 ', - b'\xf1\x00IGhe SCC FHCUP 1.00 1.02 99110-M9000 ', - ], - }, - CAR.HYUNDAI_GENESIS: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS 1.1 -150210', - b'\xf1\x00DH LKAS 1.4 -140110', - b'\xf1\x00DH LKAS 1.5 -140425', - ], - }, - CAR.HYUNDAI_IONIQ: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_PHEV_2019: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2551 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT AUS RHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_PHEV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2210 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - ], - }, - CAR.HYUNDAI_IONIQ_EV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7500 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7100 ', - b'\xf1\x00AEev SCC FHCUP 1.00 1.01 99110-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7510 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', - b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - ], - }, - CAR.HYUNDAI_IONIQ_EV_LTD: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', - b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - ], - }, - CAR.HYUNDAI_SONATA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', - b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', - b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', - b'\xf1\x00DN ESC \x06 107"\x08\x07 58910-L0100', - b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', - b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0200 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', - b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - }, - CAR.HYUNDAI_SONATA_LF: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', - b'\xf1\x00LF ESC \x0c 11 \x17\x01\x13 58920-C2610', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', - b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', - ], - }, - CAR.HYUNDAI_TUCSON: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', - b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', - b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', - ], - }, - CAR.HYUNDAI_SANTA_FE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', - b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', - b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', - b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', - b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', - b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', - b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', - b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', - b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', - ], - }, - CAR.HYUNDAI_SANTA_FE_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.01 99110-S1500 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x01 104"\x10\x07 58910-S2DA0', - b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', - b'\xf1\x00TM ESC \x03 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', - b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', - b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - ], - }, - CAR.HYUNDAI_SANTA_FE_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', - b'\xf1\x00TM MDPS C 1.00 1.02 56310GA000\x00 4TSHA100', - b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', - b'\xf1\x00TM MDPS R 1.00 1.06 57700-CL000 4TSHP106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT KOR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - }, - CAR.HYUNDAI_SANTA_FE_PHEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC F-CUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - }, - CAR.HYUNDAI_CUSTIN_1ST_GEN: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', - ], - }, - CAR.KIA_STINGER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', - b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', - ], - }, - CAR.KIA_STINGER_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.01 99110-J5100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5320 4C2VL503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5520 4C4VL503', - b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 99211-J5000 201209', - ], - }, - CAR.HYUNDAI_PALISADE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.03 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.00 99110-S9110 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.03 99110-S9100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 104 \x10\x15 58910-S8350', - b'\xf1\x00LX ESC \x01 104 \x10\x16 58910-S8360', - b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', - b'\xf1\x00LX ESC \x0b 101\x19\x03 58910-S8360', - b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', - b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', - b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', - b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', - b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', - b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', - b'\xf1\x00ON ESC \x0b 103$\x04\x08 58910-S9360', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-XX000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8420 4LXDC104', - b'\xf1\x00LX2 MDPS R 1.00 1.02 56370-S8300 9318', - b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', - b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LX2 MFC AT KOR LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', - ], - }, - CAR.HYUNDAI_VELOSTER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', - b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', - b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', - ], - }, - CAR.GENESIS_G70: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - ], - }, - CAR.GENESIS_G70_2020: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9220 4I2VL106', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', - b'\xf1\x00IK MDPS R 1.00 5.09 57700-G9520 4I4VL509', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.00 99110-G9300 ', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT USA LHD 1.00 1.04 99211-G9000 220401', - ], - }, - CAR.GENESIS_G80: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DH__ SCC F-CU- 1.00 1.01 96400-B1110 ', - b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', - b'\xf1\x00DH__ SCC F-CUP 1.00 1.02 96400-B1120 ', - b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS AT EUR LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.04 95895-B1500 181213', - ], - }, - CAR.GENESIS_G90: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 ', - b'\xf1\x00HI__ SCC FHCUP 1.00 1.02 99110-D2100 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', - b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', - b'\xf1\x00HI MFC AT USA LHD 1.00 1.03 99211-D2000 190831', - ], - }, - CAR.HYUNDAI_KONA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', - ], - }, - CAR.KIA_CEED: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CD ESC \x03 102\x18\x08\x05 58920-J7350', - ], - }, - CAR.KIA_FORTE: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', - b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', - b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', - b'\xf1\x00BDm MDPS C A.01 1.01 56310M7800\x00 4BPMC101', - b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', - b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', - ], - }, - CAR.KIA_K5_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', - b'\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', - b'\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', - b'\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', - b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', - b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', - b'\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', - b'\xf1\x00DL ESC \t 102"\x08\x10 58910-L3800', - ], - }, - CAR.KIA_K5_HEV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.01 99210-L2000 191022', - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - ], - }, - CAR.HYUNDAI_KONA_EV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x02 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x03 211 \x04\x02 58520-K4000', - b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', - b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', - b'\xf1\x00OS MDPS C 1.00 1.04 56310-XX000 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', - b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', - ], - }, - CAR.HYUNDAI_KONA_EV_2022: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', - b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', - ], - }, - CAR.HYUNDAI_KONA_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', - ], - }, - CAR.KIA_NIRO_EV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', - b'\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.02 95740-Q4000 180705', - b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', - ], - }, - CAR.KIA_NIRO_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', - b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - }, - CAR.KIA_NIRO_PHEV: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.02 99110-G5100 ', - b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', - ], - }, - CAR.KIA_NIRO_PHEV_2022: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.06 99211-G5000 201028', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC F-CUP 1.00 1.00 99110-G5600 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - ], - }, - CAR.KIA_NIRO_HEV_2021: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT KOR LHD 1.00 1.04 99211-G5000 190516', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.01 99110-G5000 ', - ], - }, - CAR.KIA_SELTOS: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00SP ESC \x07 101\x19\t\x05 58910-Q5450', - b'\xf1\x00SP ESC \t 101\x19\t\x05 58910-Q5450', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00SP2 MDPS C 1.00 1.04 56300Q5200 ', - b'\xf1\x00SP2 MDPS C 1.01 1.05 56300Q5200 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', - b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', - ], - }, - CAR.KIA_OPTIMA_G4: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00JF ESC \t 17 \x16\x06# 58920-D4180', - b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21', - b'\xf1\x00JFWGN LKAS AT EUR LHD 1.00 1.01 95895-D4100 G20', - ], - }, - CAR.KIA_OPTIMA_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', - ], - (Ecu.abs, 0x7d1, None): [ - b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", - b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', - ], - }, - CAR.KIA_OPTIMA_H: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', - ], - }, - CAR.KIA_OPTIMA_H_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', - ], - }, - CAR.HYUNDAI_ELANTRA: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', - b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', - b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', - b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', - ], - }, - CAR.HYUNDAI_ELANTRA_GT_I30: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', - b'\xf1\x00PD LKAS AT USA LHD 1.00 1.02 95740-G3000 A51', - b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', - b'\xf1\x00PD MDPS C 1.00 1.03 56310/G3300 4PDDC103', - b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', - b'\xf1\x00PD ESC \x0b 103\x17\x110 58920-G3350', - b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', - b'\xf1\x00PD__ SCC F-CUP 1.01 1.00 96400-G3100 ', - b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', - ], - }, - CAR.HYUNDAI_ELANTRA_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA050 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.07 56310AA050\x00 4CNDC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.02 99210-AB000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.08 99210-AA000 220728', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', - b'\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', - b'\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', - ], - }, - CAR.HYUNDAI_ELANTRA_HEV_2021: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY050\x00 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', - ], - }, - CAR.HYUNDAI_KONA_HEV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', - ], - }, - CAR.HYUNDAI_SONATA_HYBRID: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', - b'\xf1\x00DNhe SCC FHCUP 1.00 1.00 99110-L5000 ', - b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L5000 4DNHC101', - b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', - b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8HMFC AT KOR LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - }, - CAR.KIA_SORENTO: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00UMP LKAS AT KOR LHD 1.00 1.00 95740-C5550 S30', - b'\xf1\x00UMP LKAS AT USA LHD 1.00 1.00 95740-C6550 d00', - b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00UM ESC \x02 12 \x18\x05\x05 58910-C6300', - b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330', - b'\xf1\x00UM ESC \x13 12 \x17\x07\x05 58910-C5320', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C5500 ', - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ', - ], - }, - CAR.KIA_EV6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV200 230510', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', - ], - }, - CAR.HYUNDAI_IONIQ_5: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.00 99211-GI100 230915', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI100 240110', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI010 230110', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.00 99211-GI020 230719', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI020 230719', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI100 230915', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', - ], - }, - CAR.HYUNDAI_IONIQ_6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CE MFC AT CAN LHD 1.00 1.04 99211-KL000 221213', - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.04 99211-KL000 221213', - b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', - ], - }, - CAR.HYUNDAI_TUCSON_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9260 14Y', - b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', - b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', - b'\xf1\x00NX4__ 1.00 1.02 99110-N9000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', - ], - }, - CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW020 14Z', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', - ], - }, - CAR.KIA_SPORTAGE_5TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT EUR LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1070 690', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-CH000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', - ], - }, - CAR.GENESIS_GV70_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', - ], - }, - CAR.GENESIS_GV60_EV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', - ], - }, - CAR.KIA_SORENTO_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.00 99110-R5000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', - ], - }, - CAR.KIA_SORENTO_HEV_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.10 99210-P2000 210406', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', - ], - }, - CAR.KIA_NIRO_HEV_2ND_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - }, - CAR.GENESIS_GV80: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', - ], - }, - CAR.KIA_CARNIVAL_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KA4 MFC AT EUR LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4 MFC AT KOR LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.01 99210-R0100 230710', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.05 99210-R0000 201221', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KA4_ SCC F-CUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', - ], - }, - CAR.KIA_K8_HEV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.04 99211-L8000 230207', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', - ], - }, - CAR.HYUNDAI_STARIA_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00US4 MFC AT KOR LHD 1.00 1.06 99211-CG000 230524', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00US4_ RDR ----- 1.00 1.00 99110-CG000 ', - ], - }, -} diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py deleted file mode 100644 index d2002e23e0afc2..00000000000000 --- a/selfdrive/car/hyundai/hyundaican.py +++ /dev/null @@ -1,213 +0,0 @@ -import crcmod -from openpilot.selfdrive.car.hyundai.values import CAR, HyundaiFlags - -hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) - -def create_lkas11(packer, frame, CP, apply_steer, steer_req, - torque_fault, lkas11, sys_warning, sys_state, enabled, - left_lane, right_lane, - left_lane_depart, right_lane_depart): - values = {s: lkas11[s] for s in [ - "CF_Lkas_LdwsActivemode", - "CF_Lkas_LdwsSysState", - "CF_Lkas_SysWarning", - "CF_Lkas_LdwsLHWarning", - "CF_Lkas_LdwsRHWarning", - "CF_Lkas_HbaLamp", - "CF_Lkas_FcwBasReq", - "CF_Lkas_HbaSysState", - "CF_Lkas_FcwOpt", - "CF_Lkas_HbaOpt", - "CF_Lkas_FcwSysState", - "CF_Lkas_FcwCollisionWarning", - "CF_Lkas_FusionState", - "CF_Lkas_FcwOpt_USM", - "CF_Lkas_LdwsOpt_USM", - ]} - values["CF_Lkas_LdwsSysState"] = sys_state - values["CF_Lkas_SysWarning"] = 3 if sys_warning else 0 - values["CF_Lkas_LdwsLHWarning"] = left_lane_depart - values["CF_Lkas_LdwsRHWarning"] = right_lane_depart - values["CR_Lkas_StrToqReq"] = apply_steer - values["CF_Lkas_ActToi"] = steer_req - values["CF_Lkas_ToiFlt"] = torque_fault # seems to allow actuation on CR_Lkas_StrToqReq - values["CF_Lkas_MsgCount"] = frame % 0x10 - - if CP.carFingerprint in (CAR.HYUNDAI_SONATA, CAR.HYUNDAI_PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.HYUNDAI_SANTA_FE, - CAR.HYUNDAI_IONIQ_EV_2020, CAR.HYUNDAI_IONIQ_PHEV, CAR.KIA_SELTOS, CAR.HYUNDAI_ELANTRA_2021, CAR.GENESIS_G70_2020, - CAR.HYUNDAI_ELANTRA_HEV_2021, CAR.HYUNDAI_SONATA_HYBRID, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022, - CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_IONIQ_HEV_2022, CAR.HYUNDAI_SANTA_FE_HEV_2022, - CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022, CAR.KIA_K5_HEV_2020, CAR.KIA_CEED, - CAR.HYUNDAI_AZERA_6TH_GEN, CAR.HYUNDAI_AZERA_HEV_6TH_GEN, CAR.HYUNDAI_CUSTIN_1ST_GEN): - values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) - values["CF_Lkas_LdwsOpt_USM"] = 2 - - # FcwOpt_USM 5 = Orange blinking car + lanes - # FcwOpt_USM 4 = Orange car + lanes - # FcwOpt_USM 3 = Green blinking car + lanes - # FcwOpt_USM 2 = Green car + lanes - # FcwOpt_USM 1 = White car + lanes - # FcwOpt_USM 0 = No car + lanes - values["CF_Lkas_FcwOpt_USM"] = 2 if enabled else 1 - - # SysWarning 4 = keep hands on wheel - # SysWarning 5 = keep hands on wheel (red) - # SysWarning 6 = keep hands on wheel (red) + beep - # Note: the warning is hidden while the blinkers are on - values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 - - # Likely cars lacking the ability to show individual lane lines in the dash - elif CP.carFingerprint in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL): - # SysWarning 4 = keep hands on wheel + beep - values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 - - # SysState 0 = no icons - # SysState 1-2 = white car + lanes - # SysState 3 = green car + lanes, green steering wheel - # SysState 4 = green car + lanes - values["CF_Lkas_LdwsSysState"] = 3 if enabled else 1 - values["CF_Lkas_LdwsOpt_USM"] = 2 # non-2 changes above SysState definition - - # these have no effect - values["CF_Lkas_LdwsActivemode"] = 0 - values["CF_Lkas_FcwOpt_USM"] = 0 - - elif CP.carFingerprint == CAR.HYUNDAI_GENESIS: - # This field is actually LdwsActivemode - # Genesis and Optima fault when forwarding while engaged - values["CF_Lkas_LdwsActivemode"] = 2 - - dat = packer.make_can_msg("LKAS11", 0, values)[1] - - if CP.flags & HyundaiFlags.CHECKSUM_CRC8: - # CRC Checksum as seen on 2019 Hyundai Santa Fe - dat = dat[:6] + dat[7:8] - checksum = hyundai_checksum(dat) - elif CP.flags & HyundaiFlags.CHECKSUM_6B: - # Checksum of first 6 Bytes, as seen on 2018 Kia Sorento - checksum = sum(dat[:6]) % 256 - else: - # Checksum of first 6 Bytes and last Byte as seen on 2018 Kia Stinger - checksum = (sum(dat[:6]) + dat[7]) % 256 - - values["CF_Lkas_Chksum"] = checksum - - return packer.make_can_msg("LKAS11", 0, values) - - -def create_clu11(packer, frame, clu11, button, CP): - values = {s: clu11[s] for s in [ - "CF_Clu_CruiseSwState", - "CF_Clu_CruiseSwMain", - "CF_Clu_SldMainSW", - "CF_Clu_ParityBit1", - "CF_Clu_VanzDecimal", - "CF_Clu_Vanz", - "CF_Clu_SPEED_UNIT", - "CF_Clu_DetentOut", - "CF_Clu_RheostatLevel", - "CF_Clu_CluInfo", - "CF_Clu_AmpInfo", - "CF_Clu_AliveCnt1", - ]} - values["CF_Clu_CruiseSwState"] = button - values["CF_Clu_AliveCnt1"] = frame % 0x10 - # send buttons to camera on camera-scc based cars - bus = 2 if CP.flags & HyundaiFlags.CAMERA_SCC else 0 - return packer.make_can_msg("CLU11", bus, values) - - -def create_lfahda_mfc(packer, enabled, hda_set_speed=0): - values = { - "LFA_Icon_State": 2 if enabled else 0, - "HDA_Active": 1 if hda_set_speed else 0, - "HDA_Icon_State": 2 if hda_set_speed else 0, - "HDA_VSetReq": hda_set_speed, - } - return packer.make_can_msg("LFAHDA_MFC", 0, values) - -def create_acc_commands(packer, enabled, accel, upper_jerk, idx, hud_control, set_speed, stopping, long_override, use_fca): - commands = [] - - scc11_values = { - "MainMode_ACC": 1, - "TauGapSet": hud_control.leadDistanceBars, - "VSetDis": set_speed if enabled else 0, - "AliveCounterACC": idx % 0x10, - "ObjValid": 1, # close lead makes controls tighter - "ACC_ObjStatus": 1, # close lead makes controls tighter - "ACC_ObjLatPos": 0, - "ACC_ObjRelSpd": 0, - "ACC_ObjDist": 1, # close lead makes controls tighter - } - commands.append(packer.make_can_msg("SCC11", 0, scc11_values)) - - scc12_values = { - "ACCMode": 2 if enabled and long_override else 1 if enabled else 0, - "StopReq": 1 if stopping else 0, - "aReqRaw": accel, - "aReqValue": accel, # stock ramps up and down respecting jerk limit until it reaches aReqRaw - "CR_VSM_Alive": idx % 0xF, - } - - # show AEB disabled indicator on dash with SCC12 if not sending FCA messages. - # these signals also prevent a TCS fault on non-FCA cars with alpha longitudinal - if not use_fca: - scc12_values["CF_VSM_ConfMode"] = 1 - scc12_values["AEB_Status"] = 1 # AEB disabled - - scc12_dat = packer.make_can_msg("SCC12", 0, scc12_values)[1] - scc12_values["CR_VSM_ChkSum"] = 0x10 - sum(sum(divmod(i, 16)) for i in scc12_dat) % 0x10 - - commands.append(packer.make_can_msg("SCC12", 0, scc12_values)) - - scc14_values = { - "ComfortBandUpper": 0.0, # stock usually is 0 but sometimes uses higher values - "ComfortBandLower": 0.0, # stock usually is 0 but sometimes uses higher values - "JerkUpperLimit": upper_jerk, # stock usually is 1.0 but sometimes uses higher values - "JerkLowerLimit": 5.0, # stock usually is 0.5 but sometimes uses higher values - "ACCMode": 2 if enabled and long_override else 1 if enabled else 4, # stock will always be 4 instead of 0 after first disengage - "ObjGap": 2 if hud_control.leadVisible else 0, # 5: >30, m, 4: 25-30 m, 3: 20-25 m, 2: < 20 m, 0: no lead - } - commands.append(packer.make_can_msg("SCC14", 0, scc14_values)) - - # Only send FCA11 on cars where it exists on the bus - if use_fca: - # note that some vehicles most likely have an alternate checksum/counter definition - # https://github.com/commaai/opendbc/commit/9ddcdb22c4929baf310295e832668e6e7fcfa602 - fca11_values = { - "CR_FCA_Alive": idx % 0xF, - "PAINT1_Status": 1, - "FCA_DrvSetStatus": 1, - "FCA_Status": 1, # AEB disabled - } - fca11_dat = packer.make_can_msg("FCA11", 0, fca11_values)[1] - fca11_values["CR_FCA_ChkSum"] = hyundai_checksum(fca11_dat[:7]) - commands.append(packer.make_can_msg("FCA11", 0, fca11_values)) - - return commands - -def create_acc_opt(packer): - commands = [] - - scc13_values = { - "SCCDrvModeRValue": 2, - "SCC_Equip": 1, - "Lead_Veh_Dep_Alert_USM": 2, - } - commands.append(packer.make_can_msg("SCC13", 0, scc13_values)) - - # TODO: this needs to be detected and conditionally sent on unsupported long cars - fca12_values = { - "FCA_DrvSetState": 2, - "FCA_USM": 1, # AEB disabled - } - commands.append(packer.make_can_msg("FCA12", 0, fca12_values)) - - return commands - -def create_frt_radar_opt(packer): - frt_radar11_values = { - "CF_FCA_Equip_Front_Radar": 1, - } - return packer.make_can_msg("FRT_RADAR11", 0, frt_radar11_values) diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py deleted file mode 100644 index bd46f18612a5c1..00000000000000 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ /dev/null @@ -1,223 +0,0 @@ -from openpilot.selfdrive.car import CanBusBase -from openpilot.selfdrive.car.helpers import clip -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags - - -class CanBus(CanBusBase): - def __init__(self, CP, hda2=None, fingerprint=None) -> None: - super().__init__(CP, fingerprint) - - if hda2 is None: - assert CP is not None - hda2 = CP.flags & HyundaiFlags.CANFD_HDA2.value - - # On the CAN-FD platforms, the LKAS camera is on both A-CAN and E-CAN. HDA2 cars - # have a different harness than the HDA1 and non-HDA variants in order to split - # a different bus, since the steering is done by different ECUs. - self._a, self._e = 1, 0 - if hda2: - self._a, self._e = 0, 1 - - self._a += self.offset - self._e += self.offset - self._cam = 2 + self.offset - - @property - def ECAN(self): - return self._e - - @property - def ACAN(self): - return self._a - - @property - def CAM(self): - return self._cam - - -def create_steering_messages(packer, CP, CAN, enabled, lat_active, apply_steer): - - ret = [] - - values = { - "LKA_MODE": 2, - "LKA_ICON": 2 if enabled else 1, - "TORQUE_REQUEST": apply_steer, - "LKA_ASSIST": 0, - "STEER_REQ": 1 if lat_active else 0, - "STEER_MODE": 0, - "HAS_LANE_SAFETY": 0, # hide LKAS settings - "NEW_SIGNAL_1": 0, - "NEW_SIGNAL_2": 0, - } - - if CP.flags & HyundaiFlags.CANFD_HDA2: - hda2_lkas_msg = "LKAS_ALT" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "LKAS" - if CP.openpilotLongitudinalControl: - ret.append(packer.make_can_msg("LFA", CAN.ECAN, values)) - ret.append(packer.make_can_msg(hda2_lkas_msg, CAN.ACAN, values)) - else: - ret.append(packer.make_can_msg("LFA", CAN.ECAN, values)) - - return ret - -def create_suppress_lfa(packer, CAN, hda2_lfa_block_msg, hda2_alt_steering): - suppress_msg = "CAM_0x362" if hda2_alt_steering else "CAM_0x2a4" - msg_bytes = 32 if hda2_alt_steering else 24 - - values = {f"BYTE{i}": hda2_lfa_block_msg[f"BYTE{i}"] for i in range(3, msg_bytes) if i != 7} - values["COUNTER"] = hda2_lfa_block_msg["COUNTER"] - values["SET_ME_0"] = 0 - values["SET_ME_0_2"] = 0 - values["LEFT_LANE_LINE"] = 0 - values["RIGHT_LANE_LINE"] = 0 - return packer.make_can_msg(suppress_msg, CAN.ACAN, values) - -def create_buttons(packer, CP, CAN, cnt, btn): - values = { - "COUNTER": cnt, - "SET_ME_1": 1, - "CRUISE_BUTTONS": btn, - } - - bus = CAN.ECAN if CP.flags & HyundaiFlags.CANFD_HDA2 else CAN.CAM - return packer.make_can_msg("CRUISE_BUTTONS", bus, values) - -def create_acc_cancel(packer, CP, CAN, cruise_info_copy): - # TODO: why do we copy different values here? - if CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value: - values = {s: cruise_info_copy[s] for s in [ - "COUNTER", - "CHECKSUM", - "NEW_SIGNAL_1", - "MainMode_ACC", - "ACCMode", - "ZEROS_9", - "CRUISE_STANDSTILL", - "ZEROS_5", - "DISTANCE_SETTING", - "VSetDis", - ]} - else: - values = {s: cruise_info_copy[s] for s in [ - "COUNTER", - "CHECKSUM", - "ACCMode", - "VSetDis", - "CRUISE_STANDSTILL", - ]} - values.update({ - "ACCMode": 4, - "aReqRaw": 0.0, - "aReqValue": 0.0, - }) - return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) - -def create_lfahda_cluster(packer, CAN, enabled): - values = { - "HDA_ICON": 1 if enabled else 0, - "LFA_ICON": 2 if enabled else 0, - } - return packer.make_can_msg("LFAHDA_CLUSTER", CAN.ECAN, values) - - -def create_acc_control(packer, CAN, enabled, accel_last, accel, stopping, gas_override, set_speed, hud_control): - jerk = 5 - jn = jerk / 50 - if not enabled or gas_override: - a_val, a_raw = 0, 0 - else: - a_raw = accel - a_val = clip(accel, accel_last - jn, accel_last + jn) - - values = { - "ACCMode": 0 if not enabled else (2 if gas_override else 1), - "MainMode_ACC": 1, - "StopReq": 1 if stopping else 0, - "aReqValue": a_val, - "aReqRaw": a_raw, - "VSetDis": set_speed, - "JerkLowerLimit": jerk if enabled else 1, - "JerkUpperLimit": 3.0, - - "ACC_ObjDist": 1, - "ObjValid": 0, - "OBJ_STATUS": 2, - "SET_ME_2": 0x4, - "SET_ME_3": 0x3, - "SET_ME_TMP_64": 0x64, - "DISTANCE_SETTING": hud_control.leadDistanceBars, - } - - return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) - - -def create_spas_messages(packer, CAN, frame, left_blink, right_blink): - ret = [] - - values = { - } - ret.append(packer.make_can_msg("SPAS1", CAN.ECAN, values)) - - blink = 0 - if left_blink: - blink = 3 - elif right_blink: - blink = 4 - values = { - "BLINKER_CONTROL": blink, - } - ret.append(packer.make_can_msg("SPAS2", CAN.ECAN, values)) - - return ret - - -def create_adrv_messages(packer, CAN, frame): - # messages needed to car happy after disabling - # the ADAS Driving ECU to do longitudinal control - - ret = [] - - values = { - } - ret.append(packer.make_can_msg("ADRV_0x51", CAN.ACAN, values)) - - if frame % 2 == 0: - values = { - 'AEB_SETTING': 0x1, # show AEB disabled icon - 'SET_ME_2': 0x2, - 'SET_ME_FF': 0xff, - 'SET_ME_FC': 0xfc, - 'SET_ME_9': 0x9, - } - ret.append(packer.make_can_msg("ADRV_0x160", CAN.ECAN, values)) - - if frame % 5 == 0: - values = { - 'SET_ME_1C': 0x1c, - 'SET_ME_FF': 0xff, - 'SET_ME_TMP_F': 0xf, - 'SET_ME_TMP_F_2': 0xf, - } - ret.append(packer.make_can_msg("ADRV_0x1ea", CAN.ECAN, values)) - - values = { - 'SET_ME_E1': 0xe1, - 'SET_ME_3A': 0x3a, - } - ret.append(packer.make_can_msg("ADRV_0x200", CAN.ECAN, values)) - - if frame % 20 == 0: - values = { - 'SET_ME_15': 0x15, - } - ret.append(packer.make_can_msg("ADRV_0x345", CAN.ECAN, values)) - - if frame % 100 == 0: - values = { - 'SET_ME_22': 0x22, - 'SET_ME_41': 0x41, - } - ret.append(packer.make_can_msg("ADRV_0x1da", CAN.ECAN, values)) - - return ret diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py deleted file mode 100644 index 9bb8e7ecf5c2ac..00000000000000 --- a/selfdrive/car/hyundai/interface.py +++ /dev/null @@ -1,175 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, \ - CANFD_UNSUPPORTED_LONGITUDINAL_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, \ - UNSUPPORTED_LONGITUDINAL_CAR, Buttons -from openpilot.selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.disable_ecu import disable_ecu - -Ecu = car.CarParams.Ecu -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -ENABLE_BUTTONS = (Buttons.RES_ACCEL, Buttons.SET_DECEL, Buttons.CANCEL) -BUTTONS_DICT = {Buttons.RES_ACCEL: ButtonType.accelCruise, Buttons.SET_DECEL: ButtonType.decelCruise, - Buttons.GAP_DIST: ButtonType.gapAdjustCruise, Buttons.CANCEL: ButtonType.cancel} - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "hyundai" - ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None - - # These cars have been put into dashcam only due to both a lack of users and test coverage. - # These cars likely still work fine. Once a user confirms each car works and a test route is - # added to selfdrive/car/tests/routes.py, we can remove it from this list. - # FIXME: the Optima Hybrid 2017 uses a different SCC12 checksum - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } - - hda2 = Ecu.adas in [fw.ecu for fw in car_fw] - CAN = CanBus(None, hda2, fingerprint) - - if candidate in CANFD_CAR: - # detect if car is hybrid - if 0x105 in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.HYBRID.value - elif candidate in EV_CAR: - ret.flags |= HyundaiFlags.EV.value - - # detect HDA2 with ADAS Driving ECU - if hda2: - ret.flags |= HyundaiFlags.CANFD_HDA2.value - if 0x110 in fingerprint[CAN.CAM]: - ret.flags |= HyundaiFlags.CANFD_HDA2_ALT_STEERING.value - else: - # non-HDA2 - if 0x1cf not in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value - # ICE cars do not have 0x130; GEARS message on 0x40 or 0x70 instead - if 0x130 not in fingerprint[CAN.ECAN]: - if 0x40 not in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.CANFD_ALT_GEARS_2.value - else: - ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value - if candidate not in CANFD_RADAR_SCC_CAR: - ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value - else: - # TODO: detect EV and hybrid - if candidate in HYBRID_CAR: - ret.flags |= HyundaiFlags.HYBRID.value - elif candidate in EV_CAR: - ret.flags |= HyundaiFlags.EV.value - - # Send LFA message on cars with HDA - if 0x485 in fingerprint[2]: - ret.flags |= HyundaiFlags.SEND_LFA.value - - # These cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - if 0x38d in fingerprint[0] or 0x38d in fingerprint[2]: - ret.flags |= HyundaiFlags.USE_FCA.value - - ret.steerActuatorDelay = 0.1 # Default delay - ret.steerLimitTimer = 0.4 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate == CAR.KIA_OPTIMA_G4_FL: - ret.steerActuatorDelay = 0.2 - - # *** longitudinal control *** - if candidate in CANFD_CAR: - ret.experimentalLongitudinalAvailable = candidate not in (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR) - else: - ret.experimentalLongitudinalAvailable = candidate not in (UNSUPPORTED_LONGITUDINAL_CAR | CAMERA_SCC_CAR) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - ret.pcmCruise = not ret.openpilotLongitudinalControl - - ret.stoppingControl = True - ret.startingState = True - ret.vEgoStarting = 0.1 - ret.startAccel = 1.0 - ret.longitudinalActuatorDelay = 0.5 - - # *** feature detection *** - if candidate in CANFD_CAR: - ret.enableBsm = 0x1e5 in fingerprint[CAN.ECAN] - else: - ret.enableBsm = 0x58b in fingerprint[0] - - # *** panda safety config *** - if candidate in CANFD_CAR: - cfgs = [get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd), ] - if CAN.ECAN >= 4: - cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) - ret.safetyConfigs = cfgs - - if ret.flags & HyundaiFlags.CANFD_HDA2: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 - if ret.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING - if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS - if ret.flags & HyundaiFlags.CANFD_CAMERA_SCC: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC - else: - if candidate in LEGACY_SAFETY_MODE_CAR: - # these cars require a special panda safety mode due to missing counters and checksums in the messages - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundaiLegacy)] - else: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundai, 0)] - - if candidate in CAMERA_SCC_CAR: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC - - if ret.openpilotLongitudinalControl: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG - if ret.flags & HyundaiFlags.HYBRID: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS - elif ret.flags & HyundaiFlags.EV: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS - - if candidate in (CAR.HYUNDAI_KONA, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022): - ret.flags |= HyundaiFlags.ALT_LIMITS.value - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_ALT_LIMITS - - ret.centerToFront = ret.wheelbase * 0.4 - - return ret - - @staticmethod - def init(CP, can_recv, can_send): - if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value): - addr, bus = 0x7d0, 0 - if CP.flags & HyundaiFlags.CANFD_HDA2.value: - addr, bus = 0x730, CanBus(CP).ECAN - disable_ecu(can_recv, can_send, bus=bus, addr=addr, com_cont_req=b'\x28\x83\x01') - - # for blinkers - if CP.flags & HyundaiFlags.ENABLE_BLINKERS: - disable_ecu(can_recv, can_send, bus=CanBus(CP).ECAN, addr=0x7B1, com_cont_req=b'\x28\x83\x01') - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - if self.CS.CP.openpilotLongitudinalControl: - ret.buttonEvents = create_button_events(self.CS.cruise_buttons[-1], self.CS.prev_cruise_buttons, BUTTONS_DICT) - - # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state - # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons - # Main button also can trigger an engagement on these cars - allow_enable = any(btn in ENABLE_BUTTONS for btn in self.CS.cruise_buttons) or any(self.CS.main_buttons) - events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable) - - # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) - if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: - self.low_speed_alert = True - if ret.vEgo > (self.CP.minSteerSpeed + 4.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(car.CarEvent.EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py deleted file mode 100644 index 52600509860f5a..00000000000000 --- a/selfdrive/car/hyundai/radar_interface.py +++ /dev/null @@ -1,79 +0,0 @@ -import math - -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.hyundai.values import DBC - -RADAR_START_ADDR = 0x500 -RADAR_MSG_COUNT = 32 - -# POC for parsing corner radars: https://github.com/commaai/openpilot/pull/24221/ - -def get_radar_can_parser(CP): - if DBC[CP.carFingerprint]['radar'] is None: - return None - - messages = [(f"RADAR_TRACK_{addr:x}", 50) for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT)] - return CANParser(DBC[CP.carFingerprint]['radar'], messages, 1) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.updated_messages = set() - self.trigger_msg = RADAR_START_ADDR + RADAR_MSG_COUNT - 1 - self.track_id = 0 - - self.radar_off_can = CP.radarUnavailable - self.rcp = get_radar_can_parser(CP) - - def update(self, can_strings): - if self.radar_off_can or (self.rcp is None): - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - if self.rcp is None: - return ret - - errors = [] - - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): - msg = self.rcp.vl[f"RADAR_TRACK_{addr:x}"] - - if addr not in self.pts: - self.pts[addr] = car.RadarData.RadarPoint.new_message() - self.pts[addr].trackId = self.track_id - self.track_id += 1 - - valid = msg['STATE'] in (3, 4) - if valid: - azimuth = math.radians(msg['AZIMUTH']) - self.pts[addr].measured = True - self.pts[addr].dRel = math.cos(azimuth) * msg['LONG_DIST'] - self.pts[addr].yRel = 0.5 * -math.sin(azimuth) * msg['LONG_DIST'] - self.pts[addr].vRel = msg['REL_SPEED'] - self.pts[addr].aRel = msg['REL_ACCEL'] - self.pts[addr].yvRel = float('nan') - - else: - del self.pts[addr] - - ret.points = list(self.pts.values()) - return ret diff --git a/selfdrive/car/hyundai/tests/__init__.py b/selfdrive/car/hyundai/tests/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/hyundai/tests/print_platform_codes.py b/selfdrive/car/hyundai/tests/print_platform_codes.py deleted file mode 100755 index f641535678c22f..00000000000000 --- a/selfdrive/car/hyundai/tests/print_platform_codes.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from openpilot.selfdrive.car.hyundai.values import PLATFORM_CODE_ECUS, get_platform_codes -from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -if __name__ == "__main__": - for car_model, ecus in FW_VERSIONS.items(): - print() - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - platform_codes = get_platform_codes(ecus[ecu]) - codes = {code for code, _ in platform_codes} - dates = {date for _, date in platform_codes if date is not None} - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {codes}') - print(f' Dates: {dates}') diff --git a/selfdrive/car/hyundai/tests/test_hyundai.py b/selfdrive/car/hyundai/tests/test_hyundai.py deleted file mode 100644 index 4d31d7d15e8c68..00000000000000 --- a/selfdrive/car/hyundai/tests/test_hyundai.py +++ /dev/null @@ -1,218 +0,0 @@ -from hypothesis import settings, given, strategies as st - -import pytest - -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.hyundai.values import CAMERA_SCC_CAR, CANFD_CAR, CAN_GEARS, CAR, CHECKSUM, DATE_FW_ECUS, \ - HYBRID_CAR, EV_CAR, FW_QUERY_CONFIG, LEGACY_SAFETY_MODE_CAR, CANFD_FUZZY_WHITELIST, \ - UNSUPPORTED_LONGITUDINAL_CAR, PLATFORM_CODE_ECUS, HYUNDAI_VERSION_REQUEST_LONG, \ - get_platform_codes -from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -# Some platforms have date codes in a different format we don't yet parse (or are missing). -# For now, assert list of expected missing date cars -NO_DATES_PLATFORMS = { - # CAN FD - CAR.KIA_SPORTAGE_5TH_GEN, - CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN, - CAR.HYUNDAI_TUCSON_4TH_GEN, - # CAN - CAR.HYUNDAI_ELANTRA, - CAR.HYUNDAI_ELANTRA_GT_I30, - CAR.KIA_CEED, - CAR.KIA_FORTE, - CAR.KIA_OPTIMA_G4, - CAR.KIA_OPTIMA_G4_FL, - CAR.KIA_SORENTO, - CAR.HYUNDAI_KONA, - CAR.HYUNDAI_KONA_EV, - CAR.HYUNDAI_KONA_EV_2022, - CAR.HYUNDAI_KONA_HEV, - CAR.HYUNDAI_SONATA_LF, - CAR.HYUNDAI_VELOSTER, -} - -CANFD_EXPECTED_ECUS = {Ecu.fwdCamera, Ecu.fwdRadar} - - -class TestHyundaiFingerprint: - def test_can_features(self): - # Test no EV/HEV in any gear lists (should all use ELECT_GEAR) - assert set.union(*CAN_GEARS.values()) & (HYBRID_CAR | EV_CAR) == set() - - # Test CAN FD car not in CAN feature lists - can_specific_feature_list = set.union(*CAN_GEARS.values(), *CHECKSUM.values(), LEGACY_SAFETY_MODE_CAR, UNSUPPORTED_LONGITUDINAL_CAR, CAMERA_SCC_CAR) - for car_model in CANFD_CAR: - assert car_model not in can_specific_feature_list, "CAN FD car unexpectedly found in a CAN feature list" - - def test_hybrid_ev_sets(self): - assert HYBRID_CAR & EV_CAR == set(), "Shared cars between hybrid and EV" - assert CANFD_CAR & HYBRID_CAR == set(), "Hard coding CAN FD cars as hybrid is no longer supported" - - def test_canfd_ecu_whitelist(self): - # Asserts only expected Ecus can exist in database for CAN-FD cars - for car_model in CANFD_CAR: - ecus = {fw[0] for fw in FW_VERSIONS[car_model].keys()} - ecus_not_in_whitelist = ecus - CANFD_EXPECTED_ECUS - ecu_strings = ", ".join([f"Ecu.{ECU_NAME[ecu]}" for ecu in ecus_not_in_whitelist]) - assert len(ecus_not_in_whitelist) == 0, \ - f"{car_model}: Car model has unexpected ECUs: {ecu_strings}" - - def test_blacklisted_parts(self, subtests): - # Asserts no ECUs known to be shared across platforms exist in the database. - # Tucson having Santa Cruz camera and EPS for example - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - if car_model == CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: - pytest.skip("Skip checking Santa Cruz for its parts") - - for code, _ in get_platform_codes(ecus[(Ecu.fwdCamera, 0x7c4, None)]): - if b"-" not in code: - continue - part = code.split(b"-")[1] - assert not part.startswith(b'CW'), "Car has bad part number" - - def test_correct_ecu_response_database(self, subtests): - """ - Assert standard responses for certain ECUs, since they can - respond to multiple queries with different data - """ - expected_fw_prefix = HYUNDAI_VERSION_REQUEST_LONG[1:] - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - assert all(fw.startswith(expected_fw_prefix) for fw in fws), \ - f"FW from unexpected request in database: {(ecu, fws)}" - - @settings(max_examples=100) - @given(data=st.data()) - def test_platform_codes_fuzzy_fw(self, data): - """Ensure function doesn't raise an exception""" - fw_strategy = st.lists(st.binary()) - fws = data.draw(fw_strategy) - get_platform_codes(fws) - - def test_expected_platform_codes(self, subtests): - # Ensures we don't accidentally add multiple platform codes for a car unless it is intentional - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Third and fourth character are usually EV/hybrid identifiers - codes = {code.split(b"-")[0][:2] for code, _ in get_platform_codes(fws)} - if car_model == CAR.HYUNDAI_PALISADE: - assert codes == {b"LX", b"ON"}, f"Car has unexpected platform codes: {car_model} {codes}" - elif car_model == CAR.HYUNDAI_KONA_EV and ecu[0] == Ecu.fwdCamera: - assert codes == {b"OE", b"OS"}, f"Car has unexpected platform codes: {car_model} {codes}" - else: - assert len(codes) == 1, f"Car has multiple platform codes: {car_model} {codes}" - - # Tests for platform codes, part numbers, and FW dates which Hyundai will use to fuzzy - # fingerprint in the absence of full FW matches: - def test_platform_code_ecus_available(self, subtests): - # TODO: add queries for these non-CAN FD cars to get EPS - no_eps_platforms = CANFD_CAR | {CAR.KIA_SORENTO, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H, - CAR.KIA_OPTIMA_H_G4_FL, CAR.HYUNDAI_SONATA_LF, CAR.HYUNDAI_TUCSON, CAR.GENESIS_G90, CAR.GENESIS_G80, CAR.HYUNDAI_ELANTRA} - - # Asserts ECU keys essential for fuzzy fingerprinting are available on all platforms - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for platform_code_ecu in PLATFORM_CODE_ECUS: - if platform_code_ecu in (Ecu.fwdRadar, Ecu.eps) and car_model == CAR.HYUNDAI_GENESIS: - continue - if platform_code_ecu == Ecu.eps and car_model in no_eps_platforms: - continue - assert platform_code_ecu in [e[0] for e in ecus] - - def test_fw_format(self, subtests): - # Asserts: - # - every supported ECU FW version returns one platform code - # - every supported ECU FW version has a part number - # - expected parsing of ECU FW dates - - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - codes = set() - for fw in fws: - result = get_platform_codes([fw]) - assert 1 == len(result), f"Unable to parse FW: {fw}" - codes |= result - - if ecu[0] not in DATE_FW_ECUS or car_model in NO_DATES_PLATFORMS: - assert all(date is None for _, date in codes) - else: - assert all(date is not None for _, date in codes) - - if car_model == CAR.HYUNDAI_GENESIS: - pytest.skip("No part numbers for car model") - - # Hyundai places the ECU part number in their FW versions, assert all parsable - # Some examples of valid formats: b"56310-L0010", b"56310L0010", b"56310/M6300" - assert all(b"-" in code for code, _ in codes), \ - f"FW does not have part number: {fw}" - - def test_platform_codes_spot_check(self): - # Asserts basic platform code parsing behavior for a few cases - results = get_platform_codes([b"\xf1\x00DH LKAS 1.1 -150210"]) - assert results == {(b"DH", b"150210")} - - # Some cameras and all radars do not have dates - results = get_platform_codes([b"\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 "]) - assert results == {(b"AEhe-G2000", None)} - - results = get_platform_codes([b"\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 "]) - assert results == {(b"CV1-CV000", None)} - - results = get_platform_codes([ - b"\xf1\x00DH LKAS 1.1 -150210", - b"\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ", - b"\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ", - ]) - assert results == {(b"DH", b"150210"), (b"AEhe-G2000", None), (b"CV1-CV000", None)} - - results = get_platform_codes([ - b"\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 220222", - b"\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 211103", - b"\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 190405", - b"\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 190720", - ]) - assert results == {(b"LX2-S8100", b"220222"), (b"LX2-S8100", b"211103"), - (b"ON-S9100", b"190405"), (b"ON-S9100", b"190720")} - - def test_fuzzy_excluded_platforms(self): - # Asserts a list of platforms that will not fuzzy fingerprint with platform codes due to them being shared. - # This list can be shrunk as we combine platforms and detect features - excluded_platforms = { - CAR.GENESIS_G70, # shared platform code, part number, and date - CAR.GENESIS_G70_2020, - } - excluded_platforms |= CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST # shared platform codes - excluded_platforms |= NO_DATES_PLATFORMS # date codes are required to match - - platforms_with_shared_codes = set() - for platform, fw_by_addr in FW_VERSIONS.items(): - car_fw = [] - for ecu, fw_versions in fw_by_addr.items(): - ecu_name, addr, sub_addr = ecu - for fw in fw_versions: - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) - - CP = car.CarParams.new_message(carFw=car_fw) - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) - if len(matches) == 1: - assert list(matches)[0] == platform - else: - platforms_with_shared_codes.add(platform) - - assert platforms_with_shared_codes == excluded_platforms diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py deleted file mode 100644 index 0db82a7577f69c..00000000000000 --- a/selfdrive/car/hyundai/values.py +++ /dev/null @@ -1,752 +0,0 @@ -import re -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - ACCEL_MIN = -3.5 # m/s - ACCEL_MAX = 2.0 # m/s - - def __init__(self, CP): - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 7 - self.STEER_DRIVER_ALLOWANCE = 50 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_DRIVER_FACTOR = 1 - self.STEER_THRESHOLD = 150 - self.STEER_STEP = 1 # 100 Hz - - if CP.carFingerprint in CANFD_CAR: - self.STEER_MAX = 270 - self.STEER_DRIVER_ALLOWANCE = 250 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_THRESHOLD = 250 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 - - # To determine the limit for your car, find the maximum value that the stock LKAS will request. - # If the max stock LKAS request is <384, add your car to this list. - elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.HYUNDAI_ELANTRA, CAR.HYUNDAI_ELANTRA_GT_I30, CAR.HYUNDAI_IONIQ, - CAR.HYUNDAI_IONIQ_EV_LTD, CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.HYUNDAI_SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, - CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.KIA_SORENTO): - self.STEER_MAX = 255 - - # these cars have significantly more torque than most HKG; limit to 70% of max - elif CP.flags & HyundaiFlags.ALT_LIMITS: - self.STEER_MAX = 270 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 - - # Default for most HKG - else: - self.STEER_MAX = 384 - - -class HyundaiFlags(IntFlag): - # Dynamic Flags - CANFD_HDA2 = 1 - CANFD_ALT_BUTTONS = 2 - CANFD_ALT_GEARS = 2 ** 2 - CANFD_CAMERA_SCC = 2 ** 3 - - ALT_LIMITS = 2 ** 4 - ENABLE_BLINKERS = 2 ** 5 - CANFD_ALT_GEARS_2 = 2 ** 6 - SEND_LFA = 2 ** 7 - USE_FCA = 2 ** 8 - CANFD_HDA2_ALT_STEERING = 2 ** 9 - - # these cars use a different gas signal - HYBRID = 2 ** 10 - EV = 2 ** 11 - - # Static flags - - # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. - # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py - MANDO_RADAR = 2 ** 12 - CANFD = 2 ** 13 - - # The radar does SCC on these cars when HDA I, rather than the camera - RADAR_SCC = 2 ** 14 - CAMERA_SCC = 2 ** 15 - CHECKSUM_CRC8 = 2 ** 16 - CHECKSUM_6B = 2 ** 17 - - # these cars require a special panda safety mode due to missing counters and checksums in the messages - LEGACY = 2 ** 18 - - # these cars have not been verified to work with longitudinal yet - radar disable, sending correct messages, etc. - UNSUPPORTED_LONGITUDINAL = 2 ** 19 - - CANFD_NO_RADAR_DISABLE = 2 ** 20 - - CLUSTER_GEARS = 2 ** 21 - TCU_GEARS = 2 ** 22 - - MIN_STEER_32_MPH = 2 ** 23 - - -class Footnote(Enum): - CANFD = CarFootnote( - "Requires a CAN FD panda kit if not using " + - "comma 3X for this CAN FD car.", - Column.MODEL, shop_footnote=False) - - -@dataclass -class HyundaiCarDocs(CarDocs): - package: str = "Smart Cruise Control (SCC)" - - def init_make(self, CP: car.CarParams): - if CP.flags & HyundaiFlags.CANFD: - self.footnotes.insert(0, Footnote.CANFD) - - -@dataclass -class HyundaiPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_kia_generic", None)) - - def init(self): - if self.flags & HyundaiFlags.MANDO_RADAR: - self.dbc_dict = dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated') - - if self.flags & HyundaiFlags.MIN_STEER_32_MPH: - self.specs = self.specs.override(minSteerSpeed=32 * CV.MPH_TO_MS) - - -@dataclass -class HyundaiCanFDPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_canfd", None)) - - def init(self): - self.flags |= HyundaiFlags.CANFD - - -class CAR(Platforms): - # Hyundai - HYUNDAI_AZERA_6TH_GEN = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Azera 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=1600, wheelbase=2.885, steerRatio=14.5), - ) - HYUNDAI_AZERA_HEV_6TH_GEN = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Azera Hybrid 2019", "All", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - ], - CarSpecs(mass=1675, wheelbase=2.885, steerRatio=14.5), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_ELANTRA = HyundaiPlatformConfig( - [ - # TODO: 2017-18 could be Hyundai G - HyundaiCarDocs("Hyundai Elantra 2017-18", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b])), - HyundaiCarDocs("Hyundai Elantra 2019", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), - ], - # steerRatio: 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535, stiffnessFactor settled on 1.0081302973865127 - CarSpecs(mass=1275, wheelbase=2.7, steerRatio=15.4, tireStiffnessFactor=0.385), - flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_ELANTRA_GT_I30 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Elantra GT 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Hyundai i30 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - HYUNDAI_ELANTRA.specs, - flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_ELANTRA_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=2800 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_ELANTRA_HEV_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", - car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=3017 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_GENESIS = HyundaiPlatformConfig( - [ - # TODO: check 2015 packages - HyundaiCarDocs("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), - HyundaiCarDocs("Genesis G80 2017", "All", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), - ], - CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5, minSteerSpeed=60 * CV.KPH_TO_MS), - flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.LEGACY, - ) - HYUNDAI_IONIQ = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Hybrid 2017-19", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_HEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_h]))], # TODO: confirm 2020-21 harness, - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, - ) - HYUNDAI_IONIQ_EV_LTD = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Electric 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV | HyundaiFlags.LEGACY | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_EV_2020 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Electric 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV, - ) - HYUNDAI_IONIQ_PHEV_2019 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_PHEV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_KONA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona 2020", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b]))], - CarSpecs(mass=1275, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CLUSTER_GEARS, - ) - HYUNDAI_KONA_EV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g]))], - CarSpecs(mass=1685, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV, - ) - HYUNDAI_KONA_EV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric 2022-23", car_parts=CarParts.common([CarHarness.hyundai_o]))], - CarSpecs(mass=1743, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.EV, - ) - HYUNDAI_KONA_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", - car_parts=CarParts.common([CarHarness.hyundai_r]))], - CarSpecs(mass=1740, wheelbase=2.66, steerRatio=13.6, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, - ) - HYUNDAI_KONA_HEV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_i]))], # TODO: check packages, - CarSpecs(mass=1425, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_SANTA_FE = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", - car_parts=CarParts.common([CarHarness.hyundai_d]))], - CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.766, steerRatio=16.55, tireStiffnessFactor=0.82), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SANTA_FE_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", - car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SANTA_FE_HEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_SANTA_FE_PHEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_SONATA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", - car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=1513, wheelbase=2.84, steerRatio=13.27 * 1.15, tireStiffnessFactor=0.65), # 15% higher at the center seems reasonable - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SONATA_LF = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=1536, wheelbase=2.804, steerRatio=13.27 * 1.15), # 15% higher at the center seems reasonable - - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_STARIA_4TH_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Staria 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=2205, wheelbase=3.273, steerRatio=11.94), # https://www.hyundai.com/content/dam/hyundai/au/en/models/staria-load/premium-pip-update-2023/spec-sheet/STARIA_Load_Spec-Table_March_2023_v3.1.pdf - ) - HYUNDAI_TUCSON = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Hyundai Tucson Diesel 2019", car_parts=CarParts.common([CarHarness.hyundai_l])), - ], - CarSpecs(mass=3520 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=16.1, tireStiffnessFactor=0.385), - flags=HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_PALISADE = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), - ], - CarSpecs(mass=1999, wheelbase=2.9, steerRatio=15.6 * 1.15, tireStiffnessFactor=0.63), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_VELOSTER = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=2917 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75 * 1.15, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_SONATA_HYBRID = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata Hybrid 2020-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], - HYUNDAI_SONATA.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_IONIQ_5 = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Hyundai Ioniq 5 (Non-US only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_q])), - HyundaiCarDocs("Hyundai Ioniq 5 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), - HyundaiCarDocs("Hyundai Ioniq 5 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), - ], - CarSpecs(mass=1948, wheelbase=2.97, steerRatio=14.26, tireStiffnessFactor=0.65), - flags=HyundaiFlags.EV, - ) - HYUNDAI_IONIQ_6 = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq 6 (with HDA II) 2023-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p]))], - HYUNDAI_IONIQ_5.specs, - flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, - ) - HYUNDAI_TUCSON_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson 2023-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson Plug-in Hybrid 2024", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - ], - CarSpecs(mass=1630, wheelbase=2.756, steerRatio=13.7, tireStiffnessFactor=0.385), - ) - HYUNDAI_SANTA_CRUZ_1ST_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Cruz 2022-24", car_parts=CarParts.common([CarHarness.hyundai_n]))], - # weight from Limited trim - the only supported trim, steering ratio according to Hyundai News https://www.hyundainews.com/assets/documents/original/48035-2022SantaCruzProductGuideSpecsv2081521.pdf - CarSpecs(mass=1870, wheelbase=3, steerRatio=14.2), - ) - HYUNDAI_CUSTIN_1ST_GEN = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Custin 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=1690, wheelbase=3.055, steerRatio=17), # mass: from https://www.hyundai-motor.com.tw/clicktobuy/custin#spec_0, steerRatio: from learner - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - - # Kia - KIA_FORTE = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Forte 2019-21", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), - HyundaiCarDocs("Kia Forte 2022-23", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - CarSpecs(mass=2878 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5) - ) - KIA_K5_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia K5 2021-24", car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=3381 * CV.LB_TO_KG, wheelbase=2.85, steerRatio=13.27, tireStiffnessFactor=0.5), # 2021 Kia K5 Steering Ratio (all trims) - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - KIA_K5_HEV_2020 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia K5 Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_K5_2021.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - KIA_K8_HEV_1ST_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia K8 Hybrid (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q]))], - # mass: https://carprices.ae/brands/kia/2023/k8/1.6-turbo-hybrid, steerRatio: guesstimate from K5 platform - CarSpecs(mass=1630, wheelbase=2.895, steerRatio=13.27) - ) - KIA_NIRO_EV = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), - HyundaiCarDocs("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - ], - CarSpecs(mass=3543 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=13.6, tireStiffnessFactor=0.385), # average of all the cars - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV, - ) - KIA_NIRO_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro EV 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.EV, - ) - KIA_NIRO_PHEV = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Hybrid 2018", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_d])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.MIN_STEER_32_MPH, - ) - KIA_NIRO_PHEV_2022 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.HYBRID | HyundaiFlags.MANDO_RADAR, - ) - KIA_NIRO_HEV_2021 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), - HyundaiCarDocs("Kia Niro Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.HYBRID, - ) - KIA_NIRO_HEV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_NIRO_EV.specs, - ) - KIA_OPTIMA_G4 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima 2017", "Advanced Smart Cruise Control", - car_parts=CarParts.common([CarHarness.hyundai_b]))], # TODO: may support 2016, 2018 - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - KIA_OPTIMA_G4_FL = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima 2019-20", car_parts=CarParts.common([CarHarness.hyundai_g]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, - ) - # TODO: may support adjacent years. may have a non-zero minimum steering speed - KIA_OPTIMA_H = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, - ) - KIA_OPTIMA_H_G4_FL = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, - ) - KIA_SELTOS = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Seltos 2021", car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=1337, wheelbase=2.63, steerRatio=14.56), - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - KIA_SPORTAGE_5TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Sportage 2023-24", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), - ], - # weight from SX and above trims, average of FWD and AWD version, steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications - CarSpecs(mass=1725, wheelbase=2.756, steerRatio=13.6), - ) - KIA_SORENTO = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", - car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - CarSpecs(mass=1985, wheelbase=2.78, steerRatio=14.4 * 1.1), # 10% higher at the center seems reasonable - flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, - ) - KIA_SORENTO_4TH_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Sorento 2021-23", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=3957 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms - flags=HyundaiFlags.RADAR_SCC, - ) - KIA_SORENTO_HEV_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - ], - CarSpecs(mass=4395 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms - flags=HyundaiFlags.RADAR_SCC, - ) - KIA_STINGER = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", - car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1825, wheelbase=2.78, steerRatio=14.4 * 1.15) # 15% higher at the center seems reasonable - ) - KIA_STINGER_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - KIA_STINGER.specs, - ) - KIA_CEED = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Ceed 2019", car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=1450, wheelbase=2.65, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY, - ) - KIA_EV6 = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia EV6 (Non-US only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_p])), - HyundaiCarDocs("Kia EV6 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Kia EV6 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) - ], - CarSpecs(mass=2055, wheelbase=2.9, steerRatio=16, tireStiffnessFactor=0.65), - flags=HyundaiFlags.EV, - ) - KIA_CARNIVAL_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Carnival 2022-24", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) - ], - CarSpecs(mass=2087, wheelbase=3.09, steerRatio=14.23), - flags=HyundaiFlags.RADAR_SCC, - ) - - # Genesis - GENESIS_GV60_EV_1ST_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Genesis GV60 (Advanced Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Genesis GV60 (Performance Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - ], - CarSpecs(mass=2205, wheelbase=2.9, steerRatio=12.6), # steerRatio: https://www.motor1.com/reviews/586376/2023-genesis-gv60-first-drive/#:~:text=Relative%20to%20the%20related%20Ioniq,5%2FEV6%27s%2014.3%3A1. - flags=HyundaiFlags.EV, - ) - GENESIS_G70 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G70 2018", "All", car_parts=CarParts.common([CarHarness.hyundai_f]))], - CarSpecs(mass=1640, wheelbase=2.84, steerRatio=13.56), - flags=HyundaiFlags.LEGACY, - ) - GENESIS_G70_2020 = HyundaiPlatformConfig( - [ - # TODO: 2021 MY harness is unknown - HyundaiCarDocs("Genesis G70 2019-21", "All", car_parts=CarParts.common([CarHarness.hyundai_f])), - # TODO: From 3.3T Sport Advanced 2022 & Prestige 2023 Trim, 2.0T is unknown - HyundaiCarDocs("Genesis G70 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), - ], - GENESIS_G70.specs, - flags=HyundaiFlags.MANDO_RADAR, - ) - GENESIS_GV70_1ST_GEN = HyundaiCanFDPlatformConfig( - [ - # TODO: Hyundai P is likely the correct harness for HDA II for 2.5T (unsupported due to missing ADAS ECU, is that the radar?) - HyundaiCarDocs("Genesis GV70 (2.5T Trim, without HDA II) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Genesis GV70 (3.5T Trim, without HDA II) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_m])), - ], - CarSpecs(mass=1950, wheelbase=2.87, steerRatio=14.6), - flags=HyundaiFlags.RADAR_SCC, - ) - GENESIS_G80 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G80 2018-19", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5), - flags=HyundaiFlags.LEGACY, - ) - GENESIS_G90 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G90 2017-20", "All", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=2200, wheelbase=3.15, steerRatio=12.069), - ) - GENESIS_GV80 = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Genesis GV80 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_m]))], - CarSpecs(mass=2258, wheelbase=2.95, steerRatio=14.14), - flags=HyundaiFlags.RADAR_SCC, - ) - - -class Buttons: - NONE = 0 - RES_ACCEL = 1 - SET_DECEL = 2 - GAP_DIST = 3 - CANCEL = 4 # on newer models, this is a pause/resume button - - -def get_platform_codes(fw_versions: list[bytes]) -> set[tuple[bytes, bytes | None]]: - # Returns unique, platform-specific identification codes for a set of versions - codes = set() # (code-Optional[part], date) - for fw in fw_versions: - code_match = PLATFORM_CODE_FW_PATTERN.search(fw) - part_match = PART_NUMBER_FW_PATTERN.search(fw) - date_match = DATE_FW_PATTERN.search(fw) - if code_match is not None: - code: bytes = code_match.group() - part = part_match.group() if part_match else None - date = date_match.group() if date_match else None - if part is not None: - # part number starts with generic ECU part type, add what is specific to platform - code += b"-" + part[-5:] - - codes.add((code, date)) - return codes - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - # Non-electric CAN FD platforms often do not have platform code specifiers needed - # to distinguish between hybrid and ICE. All EVs so far are either exclusively - # electric or specify electric in the platform code. - fuzzy_platform_blacklist = {str(c) for c in (CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST)} - candidates: set[str] = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform codes, within date range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & dates - codes = get_platform_codes(expected_versions) - expected_platform_codes = {code for code, _ in codes} - expected_dates = {date for _, date in codes if date is not None} - - # Found platform codes & dates - codes = get_platform_codes(live_fw_versions.get(addr, set())) - found_platform_codes = {code for code, _ in codes} - found_dates = {date for _, date in codes if date is not None} - - # Check platform code + part number matches for any found versions - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - if ecu[0] in DATE_FW_ECUS: - # If ECU can have a FW date, require it to exist - # (this excludes candidates in the database without dates) - if not len(expected_dates) or not len(found_dates): - break - - # Check any date within range in the database, format is %y%m%d - if not any(min(expected_dates) <= found_date <= max(expected_dates) for found_date in found_dates): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return candidates - fuzzy_platform_blacklist - - -HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) # Long description - -HYUNDAI_VERSION_REQUEST_ALT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf110) # Alt long description - -HYUNDAI_ECU_MANUFACTURING_DATE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.ECU_MANUFACTURING_DATE) - -HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -# Regex patterns for parsing platform code, FW date, and part number from FW versions -PLATFORM_CODE_FW_PATTERN = re.compile(b'((?<=' + HYUNDAI_VERSION_REQUEST_LONG[1:] + - b')[A-Z]{2}[A-Za-z0-9]{0,2})') -DATE_FW_PATTERN = re.compile(b'(?<=[ -])([0-9]{6}$)') -PART_NUMBER_FW_PATTERN = re.compile(b'(?<=[0-9][.,][0-9]{2} )([0-9]{5}[-/]?[A-Z][A-Z0-9]{3}[0-9])') - -# We've seen both ICE and hybrid for these platforms, and they have hybrid descriptors (e.g. MQ4 vs MQ4H) -CANFD_FUZZY_WHITELIST = {CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_K8_HEV_1ST_GEN, - # TODO: the hybrid variant is not out yet - CAR.KIA_CARNIVAL_4TH_GEN} - -# List of ECUs expected to have platform codes, camera and radar should exist on all cars -# TODO: use abs, it has the platform code and part number on many platforms -PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] -# So far we've only seen dates in fwdCamera -# TODO: there are date codes in the ABS firmware versions in hex -DATE_FW_ECUS = [Ecu.fwdCamera] - -# Note: an ECU on CAN FD cars may sometimes send 0x30080aaaaaaaaaaa (flow control continue) while we -# are attempting to query ECUs. This currently does not seem to affect fingerprinting from the camera -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # TODO: add back whitelists - # CAN queries (OBD-II port) - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - ), - - # CAN & CAN-FD queries (from camera) - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - ), - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - bus=1, - auxiliary=True, - obd_multiplexing=False, - ), - - # CAN & CAN FD query to understand the three digit date code - # HDA2 cars usually use 6 digit date codes, so skip bus 1 - Request( - [HYUNDAI_ECU_MANUFACTURING_DATE], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - logging=True, - ), - - # CAN-FD alt request logging queries for hvac and parkingAdas - Request( - [HYUNDAI_VERSION_REQUEST_ALT], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - logging=True, - ), - Request( - [HYUNDAI_VERSION_REQUEST_ALT], - [HYUNDAI_VERSION_RESPONSE], - bus=1, - auxiliary=True, - logging=True, - obd_multiplexing=False, - ), - ], - # We lose these ECUs without the comma power on these cars. - # Note that we still attempt to match with them when they are present - non_essential_ecus={ - Ecu.abs: [CAR.HYUNDAI_PALISADE, CAR.HYUNDAI_SONATA, CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_ELANTRA_2021, - CAR.HYUNDAI_SANTA_FE, CAR.HYUNDAI_KONA_EV_2022, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_CUSTIN_1ST_GEN, CAR.KIA_SORENTO, - CAR.KIA_CEED, CAR.KIA_SELTOS], - }, - extra_ecus=[ - (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms - (Ecu.parkingAdas, 0x7b1, None), # ADAS Parking ECU (may exist on all platforms) - (Ecu.hvac, 0x7b3, None), # HVAC Control Assembly - (Ecu.cornerRadar, 0x7b7, None), - (Ecu.combinationMeter, 0x7c6, None), # CAN FD Instrument cluster - ], - # Custom fuzzy fingerprinting function using platform codes, part numbers + FW dates: - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -CHECKSUM = { - "crc8": CAR.with_flags(HyundaiFlags.CHECKSUM_CRC8), - "6B": CAR.with_flags(HyundaiFlags.CHECKSUM_6B), -} - -CAN_GEARS = { - # which message has the gear. hybrid and EV use ELECT_GEAR - "use_cluster_gears": CAR.with_flags(HyundaiFlags.CLUSTER_GEARS), - "use_tcu_gears": CAR.with_flags(HyundaiFlags.TCU_GEARS), -} - -CANFD_CAR = CAR.with_flags(HyundaiFlags.CANFD) -CANFD_RADAR_SCC_CAR = CAR.with_flags(HyundaiFlags.RADAR_SCC) - -# These CAN FD cars do not accept communication control to disable the ADAS ECU, -# responds with 0x7F2822 - 'conditions not correct' -CANFD_UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.CANFD_NO_RADAR_DISABLE) - -# The camera does SCC on these cars, rather than the radar -CAMERA_SCC_CAR = CAR.with_flags(HyundaiFlags.CAMERA_SCC) - -HYBRID_CAR = CAR.with_flags(HyundaiFlags.HYBRID) - -EV_CAR = CAR.with_flags(HyundaiFlags.EV) - -LEGACY_SAFETY_MODE_CAR = CAR.with_flags(HyundaiFlags.LEGACY) - -UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.LEGACY) | CAR.with_flags(HyundaiFlags.UNSUPPORTED_LONGITUDINAL) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py deleted file mode 100644 index 4e434ec386d805..00000000000000 --- a/selfdrive/car/interfaces.py +++ /dev/null @@ -1,536 +0,0 @@ -import json -import os -import numpy as np -import tomllib -from abc import abstractmethod, ABC -from enum import StrEnum -from typing import Any, NamedTuple -from collections.abc import Callable -from functools import cache - -from cereal import car -from openpilot.common.basedir import BASEDIR -from openpilot.common.simple_kalman import KF1D, get_kalman_gain -from openpilot.selfdrive.car import DT_CTRL, apply_hysteresis, gen_empty_fingerprint, scale_rot_inertia, scale_tire_stiffness, get_friction, STD_CARGO_KG -from openpilot.selfdrive.car.can_definitions import CanData, CanRecvCallable, CanSendCallable -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.helpers import clip -from openpilot.selfdrive.car.values import PLATFORMS -from openpilot.selfdrive.controls.lib.events import Events - -ButtonType = car.CarState.ButtonEvent.Type -GearShifter = car.CarState.GearShifter -EventName = car.CarEvent.EventName - -V_CRUISE_MAX = 145 -MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS -ACCEL_MAX = 2.0 -ACCEL_MIN = -3.5 -FRICTION_THRESHOLD = 0.3 - -TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.toml') -TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.toml') -TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.toml') - -GEAR_SHIFTER_MAP: dict[str, car.CarState.GearShifter] = { - 'P': GearShifter.park, 'PARK': GearShifter.park, - 'R': GearShifter.reverse, 'REVERSE': GearShifter.reverse, - 'N': GearShifter.neutral, 'NEUTRAL': GearShifter.neutral, - 'E': GearShifter.eco, 'ECO': GearShifter.eco, - 'T': GearShifter.manumatic, 'MANUAL': GearShifter.manumatic, - 'D': GearShifter.drive, 'DRIVE': GearShifter.drive, - 'S': GearShifter.sport, 'SPORT': GearShifter.sport, - 'L': GearShifter.low, 'LOW': GearShifter.low, - 'B': GearShifter.brake, 'BRAKE': GearShifter.brake, -} - - -class LatControlInputs(NamedTuple): - lateral_acceleration: float - roll_compensation: float - vego: float - aego: float - - -TorqueFromLateralAccelCallbackType = Callable[[LatControlInputs, car.CarParams.LateralTorqueTuning, float, float, bool, bool], float] - - -@cache -def get_torque_params(): - with open(TORQUE_SUBSTITUTE_PATH, 'rb') as f: - sub = tomllib.load(f) - with open(TORQUE_PARAMS_PATH, 'rb') as f: - params = tomllib.load(f) - with open(TORQUE_OVERRIDE_PATH, 'rb') as f: - override = tomllib.load(f) - - torque_params = {} - for candidate in (sub.keys() | params.keys() | override.keys()) - {'legend'}: - if sum([candidate in x for x in [sub, params, override]]) > 1: - raise RuntimeError(f'{candidate} is defined twice in torque config') - - sub_candidate = sub.get(candidate, candidate) - - if sub_candidate in override: - out = override[sub_candidate] - elif sub_candidate in params: - out = params[sub_candidate] - else: - raise NotImplementedError(f"Did not find torque params for {sub_candidate}") - - torque_params[sub_candidate] = {key: out[i] for i, key in enumerate(params['legend'])} - if candidate in sub: - torque_params[candidate] = torque_params[sub_candidate] - - return torque_params - -# generic car and radar interfaces - -class CarInterfaceBase(ABC): - def __init__(self, CP, CarController, CarState): - self.CP = CP - - self.frame = 0 - self.steering_unpressed = 0 - self.low_speed_alert = False - self.no_steer_warning = False - self.silent_steer_warning = True - self.v_ego_cluster_seen = False - - self.CS = CarState(CP) - self.cp = self.CS.get_can_parser(CP) - self.cp_cam = self.CS.get_cam_can_parser(CP) - self.cp_adas = self.CS.get_adas_can_parser(CP) - self.cp_body = self.CS.get_body_can_parser(CP) - self.cp_loopback = self.CS.get_loopback_can_parser(CP) - self.can_parsers = [self.cp, self.cp_cam, self.cp_adas, self.cp_body, self.cp_loopback] - - dbc_name = "" if self.cp is None else self.cp.dbc_name - self.CC: CarControllerBase = CarController(dbc_name, CP) - - def apply(self, c: car.CarControl, now_nanos: int) -> tuple[car.CarControl.Actuators, list[CanData]]: - return self.CC.update(c, self.CS, now_nanos) - - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return ACCEL_MIN, ACCEL_MAX - - @classmethod - def get_non_essential_params(cls, candidate: str): - """ - Parameters essential to controlling the car may be incomplete or wrong without FW versions or fingerprints. - """ - return cls.get_params(candidate, gen_empty_fingerprint(), list(), False, False) - - @classmethod - def get_params(cls, candidate: str, fingerprint: dict[int, dict[int, int]], car_fw: list[car.CarParams.CarFw], experimental_long: bool, docs: bool): - ret = CarInterfaceBase.get_std_params(candidate) - - platform = PLATFORMS[candidate] - ret.mass = platform.config.specs.mass - ret.wheelbase = platform.config.specs.wheelbase - ret.steerRatio = platform.config.specs.steerRatio - ret.centerToFront = ret.wheelbase * platform.config.specs.centerToFrontRatio - ret.minEnableSpeed = platform.config.specs.minEnableSpeed - ret.minSteerSpeed = platform.config.specs.minSteerSpeed - ret.tireStiffnessFactor = platform.config.specs.tireStiffnessFactor - ret.flags |= int(platform.config.flags) - - ret = cls._get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs) - - # Vehicle mass is published curb weight plus assumed payload such as a human driver; notCars have no assumed payload - if not ret.notCar: - ret.mass = ret.mass + STD_CARGO_KG - - # Set params dependent on values set by the car interface - ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, ret.tireStiffnessFactor) - - return ret - - @staticmethod - @abstractmethod - def _get_params(ret: car.CarParams, candidate, fingerprint: dict[int, dict[int, int]], - car_fw: list[car.CarParams.CarFw], experimental_long: bool, docs: bool): - raise NotImplementedError - - @staticmethod - def init(CP: car.CarParams, can_recv: CanRecvCallable, can_send: CanSendCallable): - pass - - @staticmethod - def get_steer_feedforward_default(desired_angle, v_ego): - # Proportional to realigning tire momentum: lateral acceleration. - return desired_angle * (v_ego**2) - - def get_steer_feedforward_function(self): - return self.get_steer_feedforward_default - - def torque_from_lateral_accel_linear(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - return (latcontrol_inputs.lateral_acceleration / float(torque_params.latAccelFactor)) + friction - - def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - return self.torque_from_lateral_accel_linear - - # returns a set of default params to avoid repetition in car specific params - @staticmethod - def get_std_params(candidate): - ret = car.CarParams.new_message() - ret.carFingerprint = candidate - - # Car docs fields - ret.maxLateralAccel = get_torque_params()[candidate]['MAX_LAT_ACCEL_MEASURED'] - ret.autoResumeSng = True # describes whether car can resume from a stop automatically - - # standard ALC params - ret.tireStiffnessFactor = 1.0 - ret.steerControlType = car.CarParams.SteerControlType.torque - ret.minSteerSpeed = 0. - ret.wheelSpeedFactor = 1.0 - - ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars - ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this - ret.steerRatioRear = 0. # no rear steering, at least on the listed cars aboveA - ret.openpilotLongitudinalControl = False - ret.stopAccel = -2.0 - ret.stoppingDecelRate = 0.8 # brake_travel/s while trying to stop - ret.vEgoStopping = 0.5 - ret.vEgoStarting = 0.5 - ret.stoppingControl = True - ret.longitudinalTuning.kf = 1. - ret.longitudinalTuning.kpBP = [0.] - ret.longitudinalTuning.kpV = [0.] - ret.longitudinalTuning.kiBP = [0.] - ret.longitudinalTuning.kiV = [0.] - # TODO estimate car specific lag, use .15s for now - ret.longitudinalActuatorDelay = 0.15 - ret.steerLimitTimer = 1.0 - return ret - - @staticmethod - def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - params = get_torque_params()[candidate] - - tune.init('torque') - tune.torque.useSteeringAngle = use_steering_angle - tune.torque.kp = 1.0 - tune.torque.kf = 1.0 - tune.torque.ki = 0.1 - tune.torque.friction = params['FRICTION'] - tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] - tune.torque.latAccelOffset = 0.0 - tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg - - @abstractmethod - def _update(self, c: car.CarControl) -> car.CarState: - pass - - def update(self, c: car.CarControl, can_packets: list[tuple[int, list[CanData]]]) -> car.CarState: - # parse can - for cp in self.can_parsers: - if cp is not None: - cp.update_strings(can_packets) - - # get CarState - ret = self._update(c) - - ret.canValid = all(cp.can_valid for cp in self.can_parsers if cp is not None) - ret.canTimeout = any(cp.bus_timeout for cp in self.can_parsers if cp is not None) - - if ret.vEgoCluster == 0.0 and not self.v_ego_cluster_seen: - ret.vEgoCluster = ret.vEgo - else: - self.v_ego_cluster_seen = True - - # Many cars apply hysteresis to the ego dash speed - if self.CS is not None: - ret.vEgoCluster = apply_hysteresis(ret.vEgoCluster, self.CS.out.vEgoCluster, self.CS.cluster_speed_hyst_gap) - if abs(ret.vEgo) < self.CS.cluster_min_speed: - ret.vEgoCluster = 0.0 - - if ret.cruiseState.speedCluster == 0: - ret.cruiseState.speedCluster = ret.cruiseState.speed - - # copy back for next iteration - if self.CS is not None: - self.CS.out = ret.as_reader() - - return ret - - - def create_common_events(self, cs_out, extra_gears=None, pcm_enable=True, allow_enable=True, - enable_buttons=(ButtonType.accelCruise, ButtonType.decelCruise)): - events = Events() - - if cs_out.doorOpen: - events.add(EventName.doorOpen) - if cs_out.seatbeltUnlatched: - events.add(EventName.seatbeltNotLatched) - if cs_out.gearShifter != GearShifter.drive and (extra_gears is None or - cs_out.gearShifter not in extra_gears): - events.add(EventName.wrongGear) - if cs_out.gearShifter == GearShifter.reverse: - events.add(EventName.reverseGear) - if not cs_out.cruiseState.available: - events.add(EventName.wrongCarMode) - if cs_out.espDisabled: - events.add(EventName.espDisabled) - if cs_out.espActive: - events.add(EventName.espActive) - if cs_out.stockFcw: - events.add(EventName.stockFcw) - if cs_out.stockAeb: - events.add(EventName.stockAeb) - if cs_out.vEgo > MAX_CTRL_SPEED: - events.add(EventName.speedTooHigh) - if cs_out.cruiseState.nonAdaptive: - events.add(EventName.wrongCruiseMode) - if cs_out.brakeHoldActive and self.CP.openpilotLongitudinalControl: - events.add(EventName.brakeHold) - if cs_out.parkingBrake: - events.add(EventName.parkBrake) - if cs_out.accFaulted: - events.add(EventName.accFaulted) - if cs_out.steeringPressed: - events.add(EventName.steerOverride) - if cs_out.brakePressed and cs_out.standstill: - events.add(EventName.preEnableStandstill) - if cs_out.gasPressed: - events.add(EventName.gasPressedOverride) - - # Handle button presses - for b in cs_out.buttonEvents: - # Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port) - if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed): - events.add(EventName.buttonEnable) - # Disable on rising and falling edge of cancel for both stock and OP long - if b.type == ButtonType.cancel: - events.add(EventName.buttonCancel) - - # Handle permanent and temporary steering faults - self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 - if cs_out.steerFaultTemporary: - if cs_out.steeringPressed and (not self.CS.out.steerFaultTemporary or self.no_steer_warning): - self.no_steer_warning = True - else: - self.no_steer_warning = False - - # if the user overrode recently, show a less harsh alert - if self.silent_steer_warning or cs_out.standstill or self.steering_unpressed < int(1.5 / DT_CTRL): - self.silent_steer_warning = True - events.add(EventName.steerTempUnavailableSilent) - else: - events.add(EventName.steerTempUnavailable) - else: - self.no_steer_warning = False - self.silent_steer_warning = False - if cs_out.steerFaultPermanent: - events.add(EventName.steerUnavailable) - - # we engage when pcm is active (rising edge) - # enabling can optionally be blocked by the car interface - if pcm_enable: - if cs_out.cruiseState.enabled and not self.CS.out.cruiseState.enabled and allow_enable: - events.add(EventName.pcmEnable) - elif not cs_out.cruiseState.enabled: - events.add(EventName.pcmDisable) - - return events - - -class RadarInterfaceBase(ABC): - def __init__(self, CP): - self.CP = CP - self.rcp = None - self.pts = {} - self.delay = 0 - self.radar_ts = CP.radarTimeStep - self.frame = 0 - - def update(self, can_strings): - self.frame += 1 - if (self.frame % int(100 * self.radar_ts)) == 0: - return car.RadarData.new_message() - return None - - -class CarStateBase(ABC): - def __init__(self, CP): - self.CP = CP - self.car_fingerprint = CP.carFingerprint - self.out = car.CarState.new_message() - - self.cruise_buttons = 0 - self.left_blinker_cnt = 0 - self.right_blinker_cnt = 0 - self.steering_pressed_cnt = 0 - self.left_blinker_prev = False - self.right_blinker_prev = False - self.cluster_speed_hyst_gap = 0.0 - self.cluster_min_speed = 0.0 # min speed before dropping to 0 - - Q = [[0.0, 0.0], [0.0, 100.0]] - R = 0.3 - A = [[1.0, DT_CTRL], [0.0, 1.0]] - C = [[1.0, 0.0]] - x0=[[0.0], [0.0]] - K = get_kalman_gain(DT_CTRL, np.array(A), np.array(C), np.array(Q), R) - self.v_ego_kf = KF1D(x0=x0, A=A, C=C[0], K=K) - - def update_speed_kf(self, v_ego_raw): - if abs(v_ego_raw - self.v_ego_kf.x[0][0]) > 2.0: # Prevent large accelerations when car starts at non zero speed - self.v_ego_kf.set_x([[v_ego_raw], [0.0]]) - - v_ego_x = self.v_ego_kf.update(v_ego_raw) - return float(v_ego_x[0]), float(v_ego_x[1]) - - def get_wheel_speeds(self, fl, fr, rl, rr, unit=CV.KPH_TO_MS): - factor = unit * self.CP.wheelSpeedFactor - - wheelSpeeds = car.CarState.WheelSpeeds.new_message() - wheelSpeeds.fl = fl * factor - wheelSpeeds.fr = fr * factor - wheelSpeeds.rl = rl * factor - wheelSpeeds.rr = rr * factor - return wheelSpeeds - - def update_blinker_from_lamp(self, blinker_time: int, left_blinker_lamp: bool, right_blinker_lamp: bool): - """Update blinkers from lights. Enable output when light was seen within the last `blinker_time` - iterations""" - # TODO: Handle case when switching direction. Now both blinkers can be on at the same time - self.left_blinker_cnt = blinker_time if left_blinker_lamp else max(self.left_blinker_cnt - 1, 0) - self.right_blinker_cnt = blinker_time if right_blinker_lamp else max(self.right_blinker_cnt - 1, 0) - return self.left_blinker_cnt > 0, self.right_blinker_cnt > 0 - - def update_steering_pressed(self, steering_pressed, steering_pressed_min_count): - """Applies filtering on steering pressed for noisy driver torque signals.""" - self.steering_pressed_cnt += 1 if steering_pressed else -1 - self.steering_pressed_cnt = clip(self.steering_pressed_cnt, 0, steering_pressed_min_count * 2) - return self.steering_pressed_cnt > steering_pressed_min_count - - def update_blinker_from_stalk(self, blinker_time: int, left_blinker_stalk: bool, right_blinker_stalk: bool): - """Update blinkers from stalk position. When stalk is seen the blinker will be on for at least blinker_time, - or until the stalk is turned off, whichever is longer. If the opposite stalk direction is seen the blinker - is forced to the other side. On a rising edge of the stalk the timeout is reset.""" - - if left_blinker_stalk: - self.right_blinker_cnt = 0 - if not self.left_blinker_prev: - self.left_blinker_cnt = blinker_time - - if right_blinker_stalk: - self.left_blinker_cnt = 0 - if not self.right_blinker_prev: - self.right_blinker_cnt = blinker_time - - self.left_blinker_cnt = max(self.left_blinker_cnt - 1, 0) - self.right_blinker_cnt = max(self.right_blinker_cnt - 1, 0) - - self.left_blinker_prev = left_blinker_stalk - self.right_blinker_prev = right_blinker_stalk - - return bool(left_blinker_stalk or self.left_blinker_cnt > 0), bool(right_blinker_stalk or self.right_blinker_cnt > 0) - - @staticmethod - def parse_gear_shifter(gear: str | None) -> car.CarState.GearShifter: - if gear is None: - return GearShifter.unknown - return GEAR_SHIFTER_MAP.get(gear.upper(), GearShifter.unknown) - - @staticmethod - def get_can_parser(CP): - return None - - @staticmethod - def get_cam_can_parser(CP): - return None - - @staticmethod - def get_adas_can_parser(CP): - return None - - @staticmethod - def get_body_can_parser(CP): - return None - - @staticmethod - def get_loopback_can_parser(CP): - return None - - -class CarControllerBase(ABC): - def __init__(self, dbc_name: str, CP): - self.CP = CP - self.frame = 0 - - @abstractmethod - def update(self, CC: car.CarControl.Actuators, CS: car.CarState, now_nanos: int) -> tuple[car.CarControl.Actuators, list[CanData]]: - pass - - -INTERFACE_ATTR_FILE = { - "FINGERPRINTS": "fingerprints", - "FW_VERSIONS": "fingerprints", -} - -# interface-specific helpers - -def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: bool = False) -> dict[str | StrEnum, Any]: - # read all the folders in selfdrive/car and return a dict where: - # - keys are all the car models or brand names - # - values are attr values from all car folders - result = {} - for car_folder in sorted([x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]): - try: - brand_name = car_folder.split('/')[-1] - brand_values = __import__(f'openpilot.selfdrive.car.{brand_name}.{INTERFACE_ATTR_FILE.get(attr, "values")}', fromlist=[attr]) - if hasattr(brand_values, attr) or not ignore_none: - attr_data = getattr(brand_values, attr, None) - else: - continue - - if combine_brands: - if isinstance(attr_data, dict): - for f, v in attr_data.items(): - result[f] = v - else: - result[brand_name] = attr_data - except (ImportError, OSError): - pass - - return result - - -class NanoFFModel: - def __init__(self, weights_loc: str, platform: str): - self.weights_loc = weights_loc - self.platform = platform - self.load_weights(platform) - - def load_weights(self, platform: str): - with open(self.weights_loc) as fob: - self.weights = {k: np.array(v) for k, v in json.load(fob)[platform].items()} - - def relu(self, x: np.ndarray): - return np.maximum(0.0, x) - - def forward(self, x: np.ndarray): - assert x.ndim == 1 - x = (x - self.weights['input_norm_mat'][:, 0]) / (self.weights['input_norm_mat'][:, 1] - self.weights['input_norm_mat'][:, 0]) - x = self.relu(np.dot(x, self.weights['w_1']) + self.weights['b_1']) - x = self.relu(np.dot(x, self.weights['w_2']) + self.weights['b_2']) - x = self.relu(np.dot(x, self.weights['w_3']) + self.weights['b_3']) - x = np.dot(x, self.weights['w_4']) + self.weights['b_4'] - return x - - def predict(self, x: list[float], do_sample: bool = False): - x = self.forward(np.array(x)) - if do_sample: - pred = np.random.laplace(x[0], np.exp(x[1]) / self.weights['temperature']) - else: - pred = x[0] - pred = pred * (self.weights['output_norm_mat'][1] - self.weights['output_norm_mat'][0]) + self.weights['output_norm_mat'][0] - return pred diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py deleted file mode 100644 index 8ec0a340e34921..00000000000000 --- a/selfdrive/car/isotp_parallel_query.py +++ /dev/null @@ -1,172 +0,0 @@ -import time -from collections import defaultdict -from functools import partial - -from openpilot.selfdrive.car import carlog -from openpilot.selfdrive.car.can_definitions import CanData, CanRecvCallable, CanSendCallable -from openpilot.selfdrive.car.fw_query_definitions import AddrType -from panda.python.uds import CanClient, IsoTpMessage, FUNCTIONAL_ADDRS, get_rx_addr_for_tx_addr - - -class IsoTpParallelQuery: - def __init__(self, can_send: CanSendCallable, can_recv: CanRecvCallable, bus: int, addrs: list[int] | list[AddrType], - request: list[bytes], response: list[bytes], response_offset: int = 0x8, - functional_addrs: list[int] = None, debug: bool = False, response_pending_timeout: float = 10) -> None: - self.can_send = can_send - self.can_recv = can_recv - self.bus = bus - self.request = request - self.response = response - self.functional_addrs = functional_addrs or [] - self.debug = debug - self.response_pending_timeout = response_pending_timeout - - real_addrs = [a if isinstance(a, tuple) else (a, None) for a in addrs] - for tx_addr, _ in real_addrs: - assert tx_addr not in FUNCTIONAL_ADDRS, f"Functional address should be defined in functional_addrs: {hex(tx_addr)}" - - self.msg_addrs = {tx_addr: get_rx_addr_for_tx_addr(tx_addr[0], rx_offset=response_offset) for tx_addr in real_addrs} - self.msg_buffer: dict[int, list[CanData]] = defaultdict(list) - - def rx(self) -> None: - """Drain can socket and sort messages into buffers based on address""" - can_packets = self.can_recv(wait_for_one=True) - - for packet in can_packets: - for msg in packet: - if msg.src == self.bus and msg.address in self.msg_addrs.values(): - self.msg_buffer[msg.address].append(CanData(msg.address, msg.dat, msg.src)) - - def _can_tx(self, tx_addr: int, dat: bytes, bus: int): - """Helper function to send single message""" - msg = CanData(tx_addr, dat, bus) - self.can_send([msg]) - - def _can_rx(self, addr, sub_addr=None): - """Helper function to retrieve message with specified address and subadress from buffer""" - keep_msgs = [] - - if sub_addr is None: - msgs = self.msg_buffer[addr] - else: - # Filter based on subadress - msgs = [] - for m in self.msg_buffer[addr]: - first_byte = m[1][0] - if first_byte == sub_addr: - msgs.append(m) - else: - keep_msgs.append(m) - - self.msg_buffer[addr] = keep_msgs - return msgs - - def _drain_rx(self) -> None: - self.can_recv() - self.msg_buffer = defaultdict(list) - - def _create_isotp_msg(self, tx_addr: int, sub_addr: int | None, rx_addr: int): - can_client = CanClient(self._can_tx, partial(self._can_rx, rx_addr, sub_addr=sub_addr), tx_addr, rx_addr, - self.bus, sub_addr=sub_addr, debug=self.debug) - - max_len = 8 if sub_addr is None else 7 - # uses iso-tp frame separation time of 10 ms - # TODO: use single_frame_mode so ECUs can send as fast as they want, - # as well as reduces chances we process messages from previous queries - return IsoTpMessage(can_client, timeout=0, separation_time=0.01, debug=self.debug, max_len=max_len) - - def get_data(self, timeout: float, total_timeout: float = 60.) -> dict[AddrType, bytes]: - self._drain_rx() - - # Create message objects - msgs = {} - request_counter = {} - request_done = {} - for tx_addr, rx_addr in self.msg_addrs.items(): - msgs[tx_addr] = self._create_isotp_msg(*tx_addr, rx_addr) - request_counter[tx_addr] = 0 - request_done[tx_addr] = False - - # Send first request to functional addrs, subsequent responses are handled on physical addrs - if len(self.functional_addrs): - for addr in self.functional_addrs: - self._create_isotp_msg(addr, None, -1).send(self.request[0]) - - # Send first frame (single or first) to all addresses and receive asynchronously in the loop below. - # If querying functional addrs, only set up physical IsoTpMessages to send consecutive frames - for msg in msgs.values(): - msg.send(self.request[0], setup_only=len(self.functional_addrs) > 0) - - results = {} - start_time = time.monotonic() - addrs_responded = set() # track addresses that have ever sent a valid iso-tp frame for timeout logging - response_timeouts = {tx_addr: start_time + timeout for tx_addr in self.msg_addrs} - while True: - self.rx() - - for tx_addr, msg in msgs.items(): - try: - dat, rx_in_progress = msg.recv() - except Exception: - carlog.exception(f"Error processing UDS response: {tx_addr}") - request_done[tx_addr] = True - continue - - # Extend timeout for each consecutive ISO-TP frame to avoid timing out on long responses - if rx_in_progress: - addrs_responded.add(tx_addr) - response_timeouts[tx_addr] = time.monotonic() + timeout - - if dat is None: - continue - - # Log unexpected empty responses - if len(dat) == 0: - carlog.error(f"iso-tp query empty response: {tx_addr}") - request_done[tx_addr] = True - continue - - counter = request_counter[tx_addr] - expected_response = self.response[counter] - response_valid = dat.startswith(expected_response) - - if response_valid: - if counter + 1 < len(self.request): - response_timeouts[tx_addr] = time.monotonic() + timeout - msg.send(self.request[counter + 1]) - request_counter[tx_addr] += 1 - else: - results[tx_addr] = dat[len(expected_response):] - request_done[tx_addr] = True - else: - error_code = dat[2] if len(dat) > 2 else -1 - if error_code == 0x78: - response_timeouts[tx_addr] = time.monotonic() + self.response_pending_timeout - carlog.error(f"iso-tp query response pending: {tx_addr}") - else: - request_done[tx_addr] = True - carlog.error(f"iso-tp query bad response: {tx_addr} - 0x{dat.hex()}") - - # Mark request done if address timed out - cur_time = time.monotonic() - for tx_addr in response_timeouts: - if cur_time - response_timeouts[tx_addr] > 0: - if not request_done[tx_addr]: - if request_counter[tx_addr] > 0: - carlog.error(f"iso-tp query timeout after receiving partial response: {tx_addr}") - elif tx_addr in addrs_responded: - carlog.error(f"iso-tp query timeout while receiving response: {tx_addr}") - # TODO: handle functional addresses - # else: - # carlog.error(f"iso-tp query timeout with no response: {tx_addr}") - request_done[tx_addr] = True - - # Break if all requests are done (finished or timed out) - if all(request_done.values()): - break - - if cur_time - start_time > total_timeout: - carlog.error("iso-tp query timeout while receiving data") - break - - return results diff --git a/selfdrive/car/mazda/__init__.py b/selfdrive/car/mazda/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py deleted file mode 100644 index 910e2303d805ba..00000000000000 --- a/selfdrive/car/mazda/carcontroller.py +++ /dev/null @@ -1,65 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.mazda import mazdacan -from openpilot.selfdrive.car.mazda.values import CarControllerParams, Buttons - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.apply_steer_last = 0 - self.packer = CANPacker(dbc_name) - self.brake_counter = 0 - - def update(self, CC, CS, now_nanos): - can_sends = [] - - apply_steer = 0 - - if CC.latActive: - # calculate steer and also set limits due to driver torque - new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, - CS.out.steeringTorque, CarControllerParams) - - if CC.cruiseControl.cancel: - # If brake is pressed, let us wait >70ms before trying to disable crz to avoid - # a race condition with the stock system, where the second cancel from openpilot - # will disable the crz 'main on'. crz ctrl msg runs at 50hz. 70ms allows us to - # read 3 messages and most likely sync state before we attempt cancel. - self.brake_counter = self.brake_counter + 1 - if self.frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): - # Cancel Stock ACC if it's enabled while OP is disengaged - # Send at a rate of 10hz until we sync with stock ACC state - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.CANCEL)) - else: - self.brake_counter = 0 - if CC.cruiseControl.resume and self.frame % 5 == 0: - # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds - # Send Resume button when planner wants car to move - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.RESUME)) - - self.apply_steer_last = apply_steer - - # send HUD alerts - if self.frame % 50 == 0: - ldw = CC.hudControl.visualAlert == VisualAlert.ldw - steer_required = CC.hudControl.visualAlert == VisualAlert.steerRequired - # TODO: find a way to silence audible warnings so we can add more hud alerts - steer_required = steer_required and CS.lkas_allowed_speed - can_sends.append(mazdacan.create_alert_command(self.packer, CS.cam_laneinfo, ldw, steer_required)) - - # send steering command - can_sends.append(mazdacan.create_steering_control(self.packer, self.CP, - self.frame, apply_steer, CS.cam_lkas)) - - new_actuators = CC.actuators.as_builder() - new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX - new_actuators.steerOutputCan = apply_steer - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py deleted file mode 100644 index 83aa09b66b294c..00000000000000 --- a/selfdrive/car/mazda/carstate.py +++ /dev/null @@ -1,153 +0,0 @@ -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.mazda.values import DBC, LKAS_LIMITS, MazdaFlags - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["GEAR"]["GEAR"] - - self.crz_btns_counter = 0 - self.acc_active_last = False - self.low_speed_alert = False - self.lkas_allowed_speed = False - self.lkas_disabled = False - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRZ_BTNS"]["DISTANCE_LESS"] - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["FL"], - cp.vl["WHEEL_SPEEDS"]["FR"], - cp.vl["WHEEL_SPEEDS"]["RL"], - cp.vl["WHEEL_SPEEDS"]["RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - - # Match panda speed reading - speed_kph = cp.vl["ENGINE_DATA"]["SPEED"] - ret.standstill = speed_kph <= .1 - - can_gear = int(cp.vl["GEAR"]["GEAR"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - ret.genericToggle = bool(cp.vl["BLINK_INFO"]["HIGH_BEAMS"]) - ret.leftBlindspot = cp.vl["BSM"]["LEFT_BS_STATUS"] != 0 - ret.rightBlindspot = cp.vl["BSM"]["RIGHT_BS_STATUS"] != 0 - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(40, cp.vl["BLINK_INFO"]["LEFT_BLINK"] == 1, - cp.vl["BLINK_INFO"]["RIGHT_BLINK"] == 1) - - ret.steeringAngleDeg = cp.vl["STEER"]["STEER_ANGLE"] - ret.steeringTorque = cp.vl["STEER_TORQUE"]["STEER_TORQUE_SENSOR"] - ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD - - ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]["STEER_TORQUE_MOTOR"] - ret.steeringRateDeg = cp.vl["STEER_RATE"]["STEER_ANGLE_RATE"] - - # TODO: this should be from 0 - 1. - ret.brakePressed = cp.vl["PEDALS"]["BRAKE_ON"] == 1 - ret.brake = cp.vl["BRAKE"]["BRAKE_PRESSURE"] - - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["DRIVER_SEATBELT"] == 0 - ret.doorOpen = any([cp.vl["DOORS"]["FL"], cp.vl["DOORS"]["FR"], - cp.vl["DOORS"]["BL"], cp.vl["DOORS"]["BR"]]) - - # TODO: this should be from 0 - 1. - ret.gas = cp.vl["ENGINE_DATA"]["PEDAL_GAS"] - ret.gasPressed = ret.gas > 0 - - # Either due to low speed or hands off - lkas_blocked = cp.vl["STEER_RATE"]["LKAS_BLOCK"] == 1 - - if self.CP.minSteerSpeed > 0: - # LKAS is enabled at 52kph going up and disabled at 45kph going down - # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes - if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: - self.lkas_allowed_speed = True - elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: - self.lkas_allowed_speed = False - else: - self.lkas_allowed_speed = True - - # TODO: the signal used for available seems to be the adaptive cruise signal, instead of the main on - # it should be used for carState.cruiseState.nonAdaptive instead - ret.cruiseState.available = cp.vl["CRZ_CTRL"]["CRZ_AVAILABLE"] == 1 - ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1 - ret.cruiseState.standstill = cp.vl["PEDALS"]["STANDSTILL"] == 1 - ret.cruiseState.speed = cp.vl["CRZ_EVENTS"]["CRZ_SPEED"] * CV.KPH_TO_MS - - if ret.cruiseState.enabled: - if not self.lkas_allowed_speed and self.acc_active_last: - self.low_speed_alert = True - else: - self.low_speed_alert = False - - # Check if LKAS is disabled due to lack of driver torque when all other states indicate - # it should be enabled (steer lockout). Don't warn until we actually get lkas active - # and lose it again, i.e, after initial lkas activation - ret.steerFaultTemporary = self.lkas_allowed_speed and lkas_blocked - - self.acc_active_last = ret.cruiseState.enabled - - self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] - - # camera signals - self.lkas_disabled = cp_cam.vl["CAM_LANEINFO"]["LANE_LINES"] == 0 - self.cam_lkas = cp_cam.vl["CAM_LKAS"] - self.cam_laneinfo = cp_cam.vl["CAM_LANEINFO"] - ret.steerFaultPermanent = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1 - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("BLINK_INFO", 10), - ("STEER", 67), - ("STEER_RATE", 83), - ("STEER_TORQUE", 83), - ("WHEEL_SPEEDS", 100), - ] - - if CP.flags & MazdaFlags.GEN1: - messages += [ - ("ENGINE_DATA", 100), - ("CRZ_CTRL", 50), - ("CRZ_EVENTS", 50), - ("CRZ_BTNS", 10), - ("PEDALS", 50), - ("BRAKE", 50), - ("SEATBELT", 10), - ("DOORS", 10), - ("GEAR", 20), - ("BSM", 10), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.flags & MazdaFlags.GEN1: - messages += [ - # sig_address, frequency - ("CAM_LANEINFO", 2), - ("CAM_LKAS", 16), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/mazda/fingerprints.py b/selfdrive/car/mazda/fingerprints.py deleted file mode 100644 index c7b331b1cbdbee..00000000000000 --- a/selfdrive/car/mazda/fingerprints.py +++ /dev/null @@ -1,266 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.mazda.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.MAZDA_CX5_2022: { - (Ecu.eps, 0x730, None): [ - b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PW67-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2D-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PW66-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJ3-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX5: { - (Ecu.eps, 0x730, None): [ - b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2E-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX9: { - (Ecu.eps, 0x730, None): [ - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_3: { - (Ecu.eps, 0x730, None): [ - b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_6: { - (Ecu.eps, 0x730, None): [ - b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GFBC-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX4F-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GDDM-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH3-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX9_2021: { - (Ecu.eps, 0x730, None): [ - b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py deleted file mode 100755 index fcec6b18b01b84..00000000000000 --- a/selfdrive/car/mazda/interface.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.mazda.values import CAR, LKAS_LIMITS -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "mazda" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)] - ret.radarUnavailable = True - - ret.dashcamOnly = candidate not in (CAR.MAZDA_CX5_2022, CAR.MAZDA_CX9_2021) - - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.8 - - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate not in (CAR.MAZDA_CX5_2022, ): - ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS - - ret.centerToFront = ret.wheelbase * 0.41 - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - # TODO: add button types for inc and dec - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret) - - if self.CS.lkas_disabled: - events.add(EventName.lkasDisabled) - elif self.CS.low_speed_alert: - events.add(EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/mazda/mazdacan.py b/selfdrive/car/mazda/mazdacan.py deleted file mode 100644 index 74f6af04c56631..00000000000000 --- a/selfdrive/car/mazda/mazdacan.py +++ /dev/null @@ -1,128 +0,0 @@ -from openpilot.selfdrive.car.mazda.values import Buttons, MazdaFlags - - -def create_steering_control(packer, CP, frame, apply_steer, lkas): - - tmp = apply_steer + 2048 - - lo = tmp & 0xFF - hi = tmp >> 8 - - # copy values from camera - b1 = int(lkas["BIT_1"]) - er1 = int(lkas["ERR_BIT_1"]) - lnv = 0 - ldw = 0 - er2 = int(lkas["ERR_BIT_2"]) - - # Some older models do have these, newer models don't. - # Either way, they all work just fine if set to zero. - steering_angle = 0 - b2 = 0 - - tmp = steering_angle + 2048 - ahi = tmp >> 10 - amd = (tmp & 0x3FF) >> 2 - amd = (amd >> 4) | (( amd & 0xF) << 4) - alo = (tmp & 0x3) << 2 - - ctr = frame % 16 - # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] - csum = 249 - ctr - hi - lo - (lnv << 3) - er1 - (ldw << 7) - ( er2 << 4) - (b1 << 5) - - # bytes [ 5 ] [ 6 ] [ 7 ] - csum = csum - ahi - amd - alo - b2 - - if ahi == 1: - csum = csum + 15 - - if csum < 0: - if csum < -256: - csum = csum + 512 - else: - csum = csum + 256 - - csum = csum % 256 - - values = {} - if CP.flags & MazdaFlags.GEN1: - values = { - "LKAS_REQUEST": apply_steer, - "CTR": ctr, - "ERR_BIT_1": er1, - "LINE_NOT_VISIBLE" : lnv, - "LDW": ldw, - "BIT_1": b1, - "ERR_BIT_2": er2, - "STEERING_ANGLE": steering_angle, - "ANGLE_ENABLED": b2, - "CHKSUM": csum - } - - return packer.make_can_msg("CAM_LKAS", 0, values) - - -def create_alert_command(packer, cam_msg: dict, ldw: bool, steer_required: bool): - values = {s: cam_msg[s] for s in [ - "LINE_VISIBLE", - "LINE_NOT_VISIBLE", - "LANE_LINES", - "BIT1", - "BIT2", - "BIT3", - "NO_ERR_BIT", - "S1", - "S1_HBEAM", - ]} - values.update({ - # TODO: what's the difference between all these? do we need to send all? - "HANDS_WARN_3_BITS": 0b111 if steer_required else 0, - "HANDS_ON_STEER_WARN": steer_required, - "HANDS_ON_STEER_WARN_2": steer_required, - - # TODO: right lane works, left doesn't - # TODO: need to do something about L/R - "LDW_WARN_LL": 0, - "LDW_WARN_RL": 0, - }) - return packer.make_can_msg("CAM_LANEINFO", 0, values) - - -def create_button_cmd(packer, CP, counter, button): - - can = int(button == Buttons.CANCEL) - res = int(button == Buttons.RESUME) - - if CP.flags & MazdaFlags.GEN1: - values = { - "CAN_OFF": can, - "CAN_OFF_INV": (can + 1) % 2, - - "SET_P": 0, - "SET_P_INV": 1, - - "RES": res, - "RES_INV": (res + 1) % 2, - - "SET_M": 0, - "SET_M_INV": 1, - - "DISTANCE_LESS": 0, - "DISTANCE_LESS_INV": 1, - - "DISTANCE_MORE": 0, - "DISTANCE_MORE_INV": 1, - - "MODE_X": 0, - "MODE_X_INV": 1, - - "MODE_Y": 0, - "MODE_Y_INV": 1, - - "BIT1": 1, - "BIT2": 1, - "BIT3": 1, - "CTR": (counter + 1) % 16, - } - - return packer.make_can_msg("CRZ_BTNS", 0, values) diff --git a/selfdrive/car/mazda/radar_interface.py b/selfdrive/car/mazda/radar_interface.py deleted file mode 100755 index b461fcd5f84062..00000000000000 --- a/selfdrive/car/mazda/radar_interface.py +++ /dev/null @@ -1,5 +0,0 @@ -#!/usr/bin/env python3 -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py deleted file mode 100644 index cfd7067db60841..00000000000000 --- a/selfdrive/car/mazda/values.py +++ /dev/null @@ -1,104 +0,0 @@ -from dataclasses import dataclass, field -from enum import IntFlag - -from cereal import car -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -# Steer torque limits - -class CarControllerParams: - STEER_MAX = 800 # theoretical max_steer 2047 - STEER_DELTA_UP = 10 # torque increase per refresh - STEER_DELTA_DOWN = 25 # torque decrease per refresh - STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting - STEER_DRIVER_MULTIPLIER = 1 # weight driver torque - STEER_DRIVER_FACTOR = 1 # from dbc - STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor - STEER_STEP = 1 # 100 Hz - - def __init__(self, CP): - pass - - -@dataclass -class MazdaCarDocs(CarDocs): - package: str = "All" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.mazda])) - - -@dataclass(frozen=True, kw_only=True) -class MazdaCarSpecs(CarSpecs): - tireStiffnessFactor: float = 0.7 # not optimized yet - - -class MazdaFlags(IntFlag): - # Static flags - # Gen 1 hardware: same CAN messages and same camera - GEN1 = 1 - - -@dataclass -class MazdaPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('mazda_2017', None)) - flags: int = MazdaFlags.GEN1 - - -class CAR(Platforms): - MAZDA_CX5 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-5 2017-21")], - MazdaCarSpecs(mass=3655 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.5) - ) - MAZDA_CX9 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2016-20")], - MazdaCarSpecs(mass=4217 * CV.LB_TO_KG, wheelbase=3.1, steerRatio=17.6) - ) - MAZDA_3 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda 3 2017-18")], - MazdaCarSpecs(mass=2875 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=14.0) - ) - MAZDA_6 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda 6 2017-20")], - MazdaCarSpecs(mass=3443 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=15.5) - ) - MAZDA_CX9_2021 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2021-23", video_link="https://youtu.be/dA3duO4a0O4")], - MAZDA_CX9.specs - ) - MAZDA_CX5_2022 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-5 2022-24")], - MAZDA_CX5.specs, - ) - - -class LKAS_LIMITS: - STEER_THRESHOLD = 15 - DISABLE_SPEED = 45 # kph - ENABLE_SPEED = 52 # kph - - -class Buttons: - NONE = 0 - SET_PLUS = 1 - SET_MINUS = 2 - RESUME = 3 - CANCEL = 4 - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - bus=0, - ), - ], -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/mock/__init__.py b/selfdrive/car/mock/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/mock/carcontroller.py b/selfdrive/car/mock/carcontroller.py deleted file mode 100644 index 0cd37c03695d53..00000000000000 --- a/selfdrive/car/mock/carcontroller.py +++ /dev/null @@ -1,5 +0,0 @@ -from openpilot.selfdrive.car.interfaces import CarControllerBase - -class CarController(CarControllerBase): - def update(self, CC, CS, now_nanos): - return CC.actuators.as_builder(), [] diff --git a/selfdrive/car/mock/carstate.py b/selfdrive/car/mock/carstate.py deleted file mode 100644 index ece908b51c522f..00000000000000 --- a/selfdrive/car/mock/carstate.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import CarStateBase - -class CarState(CarStateBase): - pass diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py deleted file mode 100755 index 7506bab053601f..00000000000000 --- a/selfdrive/car/mock/interface.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -import cereal.messaging as messaging -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -# mocked car interface for dashcam mode -class CarInterface(CarInterfaceBase): - def __init__(self, CP, CarController, CarState): - super().__init__(CP, CarController, CarState) - - self.speed = 0. - self.sm = messaging.SubMaster(['gpsLocation', 'gpsLocationExternal']) - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "mock" - ret.mass = 1700. - ret.wheelbase = 2.70 - ret.centerToFront = ret.wheelbase * 0.5 - ret.steerRatio = 13. - ret.dashcamOnly = True - return ret - - def _update(self, c): - self.sm.update(0) - gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' - - ret = car.CarState.new_message() - ret.vEgo = self.sm[gps_sock].speed - ret.vEgoRaw = self.sm[gps_sock].speed - - return ret diff --git a/selfdrive/car/mock/radar_interface.py b/selfdrive/car/mock/radar_interface.py deleted file mode 100644 index e654bd61fd4afd..00000000000000 --- a/selfdrive/car/mock/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/mock/values.py b/selfdrive/car/mock/values.py deleted file mode 100644 index f98aac2ee3c0ed..00000000000000 --- a/selfdrive/car/mock/values.py +++ /dev/null @@ -1,9 +0,0 @@ -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms - - -class CAR(Platforms): - MOCK = PlatformConfig( - [], - CarSpecs(mass=1700, wheelbase=2.7, steerRatio=13), - {} - ) diff --git a/selfdrive/car/nissan/__init__.py b/selfdrive/car/nissan/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py deleted file mode 100644 index 35a70ff106b3b5..00000000000000 --- a/selfdrive/car/nissan/carcontroller.py +++ /dev/null @@ -1,81 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.nissan import nissancan -from openpilot.selfdrive.car.nissan.values import CAR, CarControllerParams - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.car_fingerprint = CP.carFingerprint - - self.lkas_max_torque = 0 - self.apply_angle_last = 0 - - self.packer = CANPacker(dbc_name) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - ### STEER ### - steer_hud_alert = 1 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 - - if CC.latActive: - # windup slower - apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgoRaw, CarControllerParams) - - # Max torque from driver before EPS will give up and not apply torque - if not bool(CS.out.steeringPressed): - self.lkas_max_torque = CarControllerParams.LKAS_MAX_TORQUE - else: - # Scale max torque based on how much torque the driver is applying to the wheel - self.lkas_max_torque = max( - # Scale max torque down to half LKAX_MAX_TORQUE as a minimum - CarControllerParams.LKAS_MAX_TORQUE * 0.5, - # Start scaling torque at STEER_THRESHOLD - CarControllerParams.LKAS_MAX_TORQUE - 0.6 * max(0, abs(CS.out.steeringTorque) - CarControllerParams.STEER_THRESHOLD) - ) - - else: - apply_angle = CS.out.steeringAngleDeg - self.lkas_max_torque = 0 - - self.apply_angle_last = apply_angle - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA) and pcm_cancel_cmd: - can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg)) - - # TODO: Find better way to cancel! - # For some reason spamming the cancel button is unreliable on the Leaf - # We now cancel by making propilot think the seatbelt is unlatched, - # this generates a beep and a warning message every time you disengage - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC) and self.frame % 2 == 0: - can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, pcm_cancel_cmd)) - - can_sends.append(nissancan.create_steering_control( - self.packer, apply_angle, self.frame, CC.latActive, self.lkas_max_torque)) - - # Below are the HUD messages. We copy the stock message and modify - if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: - if self.frame % 2 == 0: - can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - - if self.frame % 50 == 0: - can_sends.append(nissancan.create_lkas_hud_info_msg( - self.packer, CS.lkas_hud_info_msg, steer_hud_alert - )) - - new_actuators = actuators.as_builder() - new_actuators.steeringAngleDeg = apply_angle - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py deleted file mode 100644 index c38173c3e369b5..00000000000000 --- a/selfdrive/car/nissan/carstate.py +++ /dev/null @@ -1,197 +0,0 @@ -import copy -from collections import deque -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.nissan.values import CAR, DBC, CarControllerParams - -TORQUE_SAMPLES = 12 - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.lkas_hud_msg = {} - self.lkas_hud_info_msg = {} - - self.steeringTorqueSamples = deque(TORQUE_SAMPLES*[0], TORQUE_SAMPLES) - self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_adas, cp_cam): - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRUISE_THROTTLE"]["FOLLOW_DISTANCE_BUTTON"] - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] - - ret.gasPressed = bool(ret.gas > 3) - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - ret.brakePressed = bool(cp.vl["CRUISE_THROTTLE"]["USER_BRAKE_PRESSED"]) - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"] == 0.0 and cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"] == 0.0 - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.cruiseState.enabled = bool(cp.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - else: - ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): - ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - if self.CP.carFingerprint == CAR.NISSAN_LEAF: - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 - elif self.CP.carFingerprint == CAR.NISSAN_LEAF_IC: - ret.seatbeltUnlatched = cp.vl["CANCEL_MSG"]["CANCEL_SEATBELT"] == 1 - ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) - elif self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.cruiseState.available = bool(cp_adas.vl["PRO_PILOT"]["CRUISE_ON"]) - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - speed = cp.vl["PROPILOT_HUD"]["SET_SPEED"] - else: - speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] - - if speed != 255: - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS - else: - conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS - ret.cruiseState.speed = speed * conversion - ret.cruiseState.speedCluster = (speed - 1) * conversion # Speed on HUD is always 1 lower than actually sent on can bus - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.steeringTorque = cp_cam.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - else: - ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - - self.steeringTorqueSamples.append(ret.steeringTorque) - # Filtering driver torque to prevent steeringPressed false positives - ret.steeringPressed = bool(abs(sum(self.steeringTorqueSamples) / TORQUE_SAMPLES) > CarControllerParams.STEER_THRESHOLD) - - ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] - - ret.leftBlinker = bool(cp.vl["LIGHTS"]["LEFT_BLINKER"]) - ret.rightBlinker = bool(cp.vl["LIGHTS"]["RIGHT_BLINKER"]) - - ret.doorOpen = any([cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RR"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RL"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FR"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FL"]]) - - ret.espDisabled = bool(cp.vl["ESP"]["ESP_DISABLED"]) - - can_gear = int(cp.vl["GEARBOX"]["GEAR_SHIFTER"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - self.lkas_enabled = bool(cp.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) - else: - self.lkas_enabled = bool(cp_adas.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) - - self.cruise_throttle_msg = copy.copy(cp.vl["CRUISE_THROTTLE"]) - - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - self.cancel_msg = copy.copy(cp.vl["CANCEL_MSG"]) - - if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: - self.lkas_hud_msg = copy.copy(cp_adas.vl["PROPILOT_HUD"]) - self.lkas_hud_info_msg = copy.copy(cp_adas.vl["PROPILOT_HUD_INFO_MSG"]) - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("STEER_ANGLE_SENSOR", 100), - ("WHEEL_SPEEDS_REAR", 50), - ("WHEEL_SPEEDS_FRONT", 50), - ("ESP", 25), - ("GEARBOX", 25), - ("DOORS_LIGHTS", 10), - ("LIGHTS", 10), - ] - - if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - messages += [ - ("GAS_PEDAL", 100), - ("CRUISE_THROTTLE", 50), - ("HUD", 25), - ] - - elif CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - messages += [ - ("BRAKE_PEDAL", 100), - ("CRUISE_THROTTLE", 50), - ("CANCEL_MSG", 50), - ("HUD_SETTINGS", 25), - ("SEATBELT", 10), - ] - - if CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages += [ - ("CRUISE_STATE", 10), - ("LKAS_SETTINGS", 10), - ("PROPILOT_HUD", 50), - ] - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) - - messages.append(("STEER_TORQUE_SENSOR", 100)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_adas_can_parser(CP): - # this function generates lists for signal, messages and initial values - - if CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages = [ - ("LKAS", 100), - ("PRO_PILOT", 100), - ] - else: - messages = [ - ("PROPILOT_HUD_INFO_MSG", 2), - ("LKAS_SETTINGS", 10), - ("CRUISE_STATE", 50), - ("PROPILOT_HUD", 50), - ("LKAS", 100), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): - messages.append(("PRO_PILOT", 100)) - elif CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages.append(("STEER_TORQUE_SENSOR", 100)) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) diff --git a/selfdrive/car/nissan/fingerprints.py b/selfdrive/car/nissan/fingerprints.py deleted file mode 100644 index 743feeace9c6f3..00000000000000 --- a/selfdrive/car/nissan/fingerprints.py +++ /dev/null @@ -1,119 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.nissan.values import CAR - -Ecu = car.CarParams.Ecu - -FINGERPRINTS = { - CAR.NISSAN_XTRAIL: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 - }, - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 - }], - CAR.NISSAN_LEAF: [{ - 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 - }, - { - 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 - }], - CAR.NISSAN_LEAF_IC: [{ - 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 - }], - CAR.NISSAN_ROGUE: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], - CAR.NISSAN_ALTIMA: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], -} - -FW_VERSIONS = { - CAR.NISSAN_ALTIMA: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86CA1D', - ], - (Ecu.eps, 0x742, None): [ - b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'237109HE2B', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U29HE0A', - ], - }, - CAR.NISSAN_LEAF: { - (Ecu.abs, 0x740, None): [ - b'476605SA1C', - b'476605SA7D', - b'476605SC2D', - b'476606WK7B', - b'476606WK9B', - ], - (Ecu.eps, 0x742, None): [ - b'5SA2A\x99A\x05\x02N123F\x15b\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SA2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SN2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.fwdCamera, 0x707, None): [ - b'5SA0ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', - b'5SA2ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', - b'6WK2ADB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', - b'6WK2BDB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', - b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SA3C', - b'284U25SP0C', - b'284U25SP1C', - b'284U26WK0A', - b'284U26WK0C', - ], - }, - CAR.NISSAN_LEAF_IC: { - (Ecu.fwdCamera, 0x707, None): [ - b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', - ], - (Ecu.abs, 0x740, None): [ - b'476605SD2E', - b'476605SH1D', - b'476605SK2A', - ], - (Ecu.eps, 0x742, None): [ - b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SF0C', - b'284U25SH3A', - b'284U25SK2D', - ], - }, - CAR.NISSAN_XTRAIL: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86FR2A', - ], - (Ecu.abs, 0x740, None): [ - b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', - b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', - ], - (Ecu.eps, 0x742, None): [ - b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.combinationMeter, 0x743, None): [ - b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U26FR0E', - ], - }, -} diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py deleted file mode 100644 index 2e9a990610a279..00000000000000 --- a/selfdrive/car/nissan/interface.py +++ /dev/null @@ -1,44 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.nissan.values import CAR - -ButtonType = car.CarState.ButtonEvent.Type - - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "nissan" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] - ret.autoResumeSng = False - - ret.steerLimitTimer = 1.0 - - ret.steerActuatorDelay = 0.1 - - ret.steerControlType = car.CarParams.SteerControlType.angle - ret.radarUnavailable = True - - if candidate == CAR.NISSAN_ALTIMA: - # Altima has EPS on C-CAN unlike the others that have it on V-CAN - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_NISSAN_ALT_EPS_BUS - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_adas, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.brake]) - - if self.CS.lkas_enabled: - events.add(car.CarEvent.EventName.invalidLkasSetting) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/nissan/nissancan.py b/selfdrive/car/nissan/nissancan.py deleted file mode 100644 index 28fb01d7e39df8..00000000000000 --- a/selfdrive/car/nissan/nissancan.py +++ /dev/null @@ -1,154 +0,0 @@ -import crcmod -from openpilot.selfdrive.car.nissan.values import CAR - -# TODO: add this checksum to the CANPacker -nissan_checksum = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) - - -def create_steering_control(packer, apply_steer, frame, steer_on, lkas_max_torque): - values = { - "COUNTER": frame % 0x10, - "DESIRED_ANGLE": apply_steer, - "SET_0x80_2": 0x80, - "SET_0x80": 0x80, - "MAX_TORQUE": lkas_max_torque if steer_on else 0, - "LKA_ACTIVE": steer_on, - } - - dat = packer.make_can_msg("LKAS", 0, values)[1] - - values["CHECKSUM"] = nissan_checksum(dat[:7]) - return packer.make_can_msg("LKAS", 0, values) - - -def create_acc_cancel_cmd(packer, car_fingerprint, cruise_throttle_msg): - values = {s: cruise_throttle_msg[s] for s in [ - "COUNTER", - "PROPILOT_BUTTON", - "CANCEL_BUTTON", - "GAS_PEDAL_INVERTED", - "SET_BUTTON", - "RES_BUTTON", - "FOLLOW_DISTANCE_BUTTON", - "NO_BUTTON_PRESSED", - "GAS_PEDAL", - "USER_BRAKE_PRESSED", - "NEW_SIGNAL_2", - "GAS_PRESSED_INVERTED", - "unsure1", - "unsure2", - "unsure3", - ]} - can_bus = 1 if car_fingerprint == CAR.NISSAN_ALTIMA else 2 - - values["CANCEL_BUTTON"] = 1 - values["NO_BUTTON_PRESSED"] = 0 - values["PROPILOT_BUTTON"] = 0 - values["SET_BUTTON"] = 0 - values["RES_BUTTON"] = 0 - values["FOLLOW_DISTANCE_BUTTON"] = 0 - - return packer.make_can_msg("CRUISE_THROTTLE", can_bus, values) - - -def create_cancel_msg(packer, cancel_msg, cruise_cancel): - values = {s: cancel_msg[s] for s in [ - "CANCEL_SEATBELT", - "NEW_SIGNAL_1", - "NEW_SIGNAL_2", - "NEW_SIGNAL_3", - ]} - - if cruise_cancel: - values["CANCEL_SEATBELT"] = 1 - - return packer.make_can_msg("CANCEL_MSG", 2, values) - - -def create_lkas_hud_msg(packer, lkas_hud_msg, enabled, left_line, right_line, left_lane_depart, right_lane_depart): - values = {s: lkas_hud_msg[s] for s in [ - "LARGE_WARNING_FLASHING", - "SIDE_RADAR_ERROR_FLASHING1", - "SIDE_RADAR_ERROR_FLASHING2", - "LEAD_CAR", - "LEAD_CAR_ERROR", - "FRONT_RADAR_ERROR", - "FRONT_RADAR_ERROR_FLASHING", - "SIDE_RADAR_ERROR_FLASHING3", - "LKAS_ERROR_FLASHING", - "SAFETY_SHIELD_ACTIVE", - "RIGHT_LANE_GREEN_FLASH", - "LEFT_LANE_GREEN_FLASH", - "FOLLOW_DISTANCE", - "AUDIBLE_TONE", - "SPEED_SET_ICON", - "SMALL_STEERING_WHEEL_ICON", - "unknown59", - "unknown55", - "unknown26", - "unknown28", - "unknown31", - "SET_SPEED", - "unknown43", - "unknown08", - "unknown05", - "unknown02", - ]} - - values["RIGHT_LANE_YELLOW_FLASH"] = 1 if right_lane_depart else 0 - values["LEFT_LANE_YELLOW_FLASH"] = 1 if left_lane_depart else 0 - - values["LARGE_STEERING_WHEEL_ICON"] = 2 if enabled else 0 - values["RIGHT_LANE_GREEN"] = 1 if right_line and enabled else 0 - values["LEFT_LANE_GREEN"] = 1 if left_line and enabled else 0 - - return packer.make_can_msg("PROPILOT_HUD", 0, values) - - -def create_lkas_hud_info_msg(packer, lkas_hud_info_msg, steer_hud_alert): - values = {s: lkas_hud_info_msg[s] for s in [ - "NA_HIGH_ACCEL_TEMP", - "SIDE_RADAR_NA_HIGH_CABIN_TEMP", - "SIDE_RADAR_MALFUNCTION", - "LKAS_MALFUNCTION", - "FRONT_RADAR_MALFUNCTION", - "SIDE_RADAR_NA_CLEAN_REAR_CAMERA", - "NA_POOR_ROAD_CONDITIONS", - "CURRENTLY_UNAVAILABLE", - "SAFETY_SHIELD_OFF", - "FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION", - "PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED", - "SIDE_IMPACT_NA_RADAR_OBSTRUCTION", - "WARNING_DO_NOT_ENTER", - "SIDE_IMPACT_SYSTEM_OFF", - "SIDE_IMPACT_MALFUNCTION", - "FRONT_COLLISION_MALFUNCTION", - "SIDE_RADAR_MALFUNCTION2", - "LKAS_MALFUNCTION2", - "FRONT_RADAR_MALFUNCTION2", - "PROPILOT_NA_MSGS", - "BOTTOM_MSG", - "HANDS_ON_WHEEL_WARNING", - "WARNING_STEP_ON_BRAKE_NOW", - "PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED", - "PROPILOT_NA_HIGH_CABIN_TEMP", - "WARNING_PROPILOT_MALFUNCTION", - "ACC_UNAVAILABLE_HIGH_CABIN_TEMP", - "ACC_NA_FRONT_CAMERA_IMPARED", - "unknown07", - "unknown10", - "unknown15", - "unknown23", - "unknown19", - "unknown31", - "unknown32", - "unknown46", - "unknown61", - "unknown55", - "unknown50", - ]} - - if steer_hud_alert: - values["HANDS_ON_WHEEL_WARNING"] = 1 - - return packer.make_can_msg("PROPILOT_HUD_INFO_MSG", 0, values) diff --git a/selfdrive/car/nissan/radar_interface.py b/selfdrive/car/nissan/radar_interface.py deleted file mode 100644 index e654bd61fd4afd..00000000000000 --- a/selfdrive/car/nissan/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py deleted file mode 100644 index eecffb21bcc0d1..00000000000000 --- a/selfdrive/car/nissan/values.py +++ /dev/null @@ -1,107 +0,0 @@ -from dataclasses import dataclass, field - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs, CarHarness, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., .8, .15]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., 3.5, 0.4]) - LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower - STEER_THRESHOLD = 1.0 - - def __init__(self, CP): - pass - - -@dataclass -class NissanCarDocs(CarDocs): - package: str = "ProPILOT Assist" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.nissan_a])) - - -@dataclass(frozen=True) -class NissanCarSpecs(CarSpecs): - centerToFrontRatio: float = 0.44 - steerRatio: float = 17. - - -@dataclass -class NissanPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('nissan_x_trail_2017_generated', None)) - - -class CAR(Platforms): - NISSAN_XTRAIL = NissanPlatformConfig( - [NissanCarDocs("Nissan X-Trail 2017")], - NissanCarSpecs(mass=1610, wheelbase=2.705) - ) - NISSAN_LEAF = NissanPlatformConfig( - [NissanCarDocs("Nissan Leaf 2018-23", video_link="https://youtu.be/vaMbtAh_0cY")], - NissanCarSpecs(mass=1610, wheelbase=2.705), - dbc_dict('nissan_leaf_2018_generated', None), - ) - # Leaf with ADAS ECU found behind instrument cluster instead of glovebox - # Currently the only known difference between them is the inverted seatbelt signal. - NISSAN_LEAF_IC = NISSAN_LEAF.override(car_docs=[]) - NISSAN_ROGUE = NissanPlatformConfig( - [NissanCarDocs("Nissan Rogue 2018-20")], - NissanCarSpecs(mass=1610, wheelbase=2.705) - ) - NISSAN_ALTIMA = NissanPlatformConfig( - [NissanCarDocs("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b]))], - NissanCarSpecs(mass=1492, wheelbase=2.824) - ) - - -DBC = CAR.create_dbc_map() - -# Default diagnostic session -NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) - -# Manufacturer specific -NISSAN_DIAGNOSTIC_REQUEST_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xda]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xda]) - -NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' -NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' - -NISSAN_RX_OFFSET = 0x20 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, logging in ((0, False), (1, True)) for request in [ - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - bus=bus, - logging=logging, - ), - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - rx_offset=NISSAN_RX_OFFSET, - bus=bus, - logging=logging, - ), - # Rogue's engine solely responds to this - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP_2, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP_2, NISSAN_VERSION_RESPONSE_KWP], - bus=bus, - logging=logging, - ), - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - rx_offset=NISSAN_RX_OFFSET, - bus=bus, - logging=logging, - ), - ]], -) diff --git a/selfdrive/car/subaru/__init__.py b/selfdrive/car/subaru/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py deleted file mode 100644 index c8c2e7417bef39..00000000000000 --- a/selfdrive/car/subaru/carcontroller.py +++ /dev/null @@ -1,143 +0,0 @@ -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance, make_tester_present_msg -from openpilot.selfdrive.car.helpers import clip, interp -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.subaru import subarucan -from openpilot.selfdrive.car.subaru.values import DBC, GLOBAL_ES_ADDR, CanBus, CarControllerParams, SubaruFlags - -# FIXME: These limits aren't exact. The real limit is more than likely over a larger time period and -# involves the total steering angle change rather than rate, but these limits work well for now -MAX_STEER_RATE = 25 # deg/s -MAX_STEER_RATE_FRAMES = 7 # tx control frames needed before torque can be cut - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.apply_steer_last = 0 - - self.cruise_button_prev = 0 - self.steer_rate_counter = 0 - - self.p = CarControllerParams(CP) - self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - # *** steering *** - if (self.frame % self.p.STEER_STEP) == 0: - apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) - - # limits due to driver torque - - new_steer = int(round(apply_steer)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) - - if not CC.latActive: - apply_steer = 0 - - if self.CP.flags & SubaruFlags.PREGLOBAL: - can_sends.append(subarucan.create_preglobal_steering_control(self.packer, self.frame // self.p.STEER_STEP, apply_steer, CC.latActive)) - else: - apply_steer_req = CC.latActive - - if self.CP.flags & SubaruFlags.STEER_RATE_LIMITED: - # Steering rate fault prevention - self.steer_rate_counter, apply_steer_req = \ - common_fault_avoidance(abs(CS.out.steeringRateDeg) > MAX_STEER_RATE, apply_steer_req, - self.steer_rate_counter, MAX_STEER_RATE_FRAMES) - - can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, apply_steer_req)) - - self.apply_steer_last = apply_steer - - # *** longitudinal *** - - if CC.longActive: - apply_throttle = int(round(interp(actuators.accel, CarControllerParams.THROTTLE_LOOKUP_BP, CarControllerParams.THROTTLE_LOOKUP_V))) - apply_rpm = int(round(interp(actuators.accel, CarControllerParams.RPM_LOOKUP_BP, CarControllerParams.RPM_LOOKUP_V))) - apply_brake = int(round(interp(actuators.accel, CarControllerParams.BRAKE_LOOKUP_BP, CarControllerParams.BRAKE_LOOKUP_V))) - - # limit min and max values - cruise_throttle = clip(apply_throttle, CarControllerParams.THROTTLE_MIN, CarControllerParams.THROTTLE_MAX) - cruise_rpm = clip(apply_rpm, CarControllerParams.RPM_MIN, CarControllerParams.RPM_MAX) - cruise_brake = clip(apply_brake, CarControllerParams.BRAKE_MIN, CarControllerParams.BRAKE_MAX) - else: - cruise_throttle = CarControllerParams.THROTTLE_INACTIVE - cruise_rpm = CarControllerParams.RPM_MIN - cruise_brake = CarControllerParams.BRAKE_MIN - - # *** alerts and pcm cancel *** - if self.CP.flags & SubaruFlags.PREGLOBAL: - if self.frame % 5 == 0: - # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep - # disengage ACC when OP is disengaged - if pcm_cancel_cmd: - cruise_button = 1 - # turn main on if off and past start-up state - elif not CS.out.cruiseState.available and CS.ready: - cruise_button = 1 - else: - cruise_button = CS.cruise_button - - # unstick previous mocked button press - if cruise_button == 1 and self.cruise_button_prev == 1: - cruise_button = 0 - self.cruise_button_prev = cruise_button - - can_sends.append(subarucan.create_preglobal_es_distance(self.packer, cruise_button, CS.es_distance_msg)) - - else: - if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, - self.CP.openpilotLongitudinalControl, CC.longActive, hud_control.leadVisible)) - - can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - - if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: - can_sends.append(subarucan.create_es_infotainment(self.packer, self.frame // 10, CS.es_infotainment_msg, hud_control.visualAlert)) - - if self.CP.openpilotLongitudinalControl: - if self.frame % 5 == 0: - can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg, - self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm)) - - can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, - self.CP.openpilotLongitudinalControl, CC.longActive, cruise_brake)) - - can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd, - self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle)) - else: - if pcm_cancel_cmd: - if not (self.CP.flags & SubaruFlags.HYBRID): - bus = CanBus.alt if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else CanBus.main - can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg["COUNTER"] + 1, CS.es_distance_msg, bus, pcm_cancel_cmd)) - - if self.CP.flags & SubaruFlags.DISABLE_EYESIGHT: - # Tester present (keeps eyesight disabled) - if self.frame % 100 == 0: - can_sends.append(make_tester_present_msg(GLOBAL_ES_ADDR, CanBus.camera, suppress_response=True)) - - # Create all of the other eyesight messages to keep the rest of the car happy when eyesight is disabled - if self.frame % 5 == 0: - can_sends.append(subarucan.create_es_highbeamassist(self.packer)) - - if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_static_1(self.packer)) - - if self.frame % 2 == 0: - can_sends.append(subarucan.create_es_static_2(self.packer)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py deleted file mode 100644 index 0501494fdddbfe..00000000000000 --- a/selfdrive/car/subaru/carstate.py +++ /dev/null @@ -1,229 +0,0 @@ -import copy -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.subaru.values import DBC, CanBus, SubaruFlags -from openpilot.selfdrive.car import CanSignalRateCalculator - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["Transmission"]["Gear"] - - self.angle_rate_calulator = CanSignalRateCalculator(50) - - def update(self, cp, cp_cam, cp_body): - ret = car.CarState.new_message() - - throttle_msg = cp.vl["Throttle"] if not (self.CP.flags & SubaruFlags.HYBRID) else cp_body.vl["Throttle_Hybrid"] - ret.gas = throttle_msg["Throttle_Pedal"] / 255. - - ret.gasPressed = ret.gas > 1e-5 - if self.CP.flags & SubaruFlags.PREGLOBAL: - ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 0 - else: - cp_brakes = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - ret.brakePressed = cp_brakes.vl["Brake_Status"]["Brake"] == 1 - - cp_es_distance = cp_body if self.CP.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.HYBRID) else cp_cam - if not (self.CP.flags & SubaruFlags.HYBRID): - eyesight_fault = bool(cp_es_distance.vl["ES_Distance"]["Cruise_Fault"]) - - # if openpilot is controlling long, an eyesight fault is a non-critical fault. otherwise it's an ACC fault - if self.CP.openpilotLongitudinalControl: - ret.carFaultedNonCritical = eyesight_fault - else: - ret.accFaulted = eyesight_fault - - cp_wheels = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - ret.wheelSpeeds = self.get_wheel_speeds( - cp_wheels.vl["Wheel_Speeds"]["FL"], - cp_wheels.vl["Wheel_Speeds"]["FR"], - cp_wheels.vl["Wheel_Speeds"]["RL"], - cp_wheels.vl["Wheel_Speeds"]["RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # continuous blinker signals for assisted lane change - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["Dashlights"]["LEFT_BLINKER"], - cp.vl["Dashlights"]["RIGHT_BLINKER"]) - - if self.CP.enableBsm: - ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1) - ret.rightBlindspot = (cp.vl["BSD_RCTA"]["R_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["R_APPROACHING"] == 1) - - cp_transmission = cp_body if self.CP.flags & SubaruFlags.HYBRID else cp - can_gear = int(cp_transmission.vl["Transmission"]["Gear"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] - - if not (self.CP.flags & SubaruFlags.PREGLOBAL): - # ideally we get this from the car, but unclear if it exists. diagnostic software doesn't even have it - ret.steeringRateDeg = self.angle_rate_calulator.update(ret.steeringAngleDeg, cp.vl["Steering_Torque"]["COUNTER"]) - - ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] - ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] - - steer_threshold = 75 if self.CP.flags & SubaruFlags.PREGLOBAL else 80 - ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold - - cp_cruise = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - if self.CP.flags & SubaruFlags.HYBRID: - ret.cruiseState.enabled = cp_cam.vl["ES_DashStatus"]['Cruise_Activated'] != 0 - ret.cruiseState.available = cp_cam.vl["ES_DashStatus"]['Cruise_On'] != 0 - else: - ret.cruiseState.enabled = cp_cruise.vl["CruiseControl"]["Cruise_Activated"] != 0 - ret.cruiseState.available = cp_cruise.vl["CruiseControl"]["Cruise_On"] != 0 - ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS - - if (self.CP.flags & SubaruFlags.PREGLOBAL and cp.vl["Dash_State2"]["UNITS"] == 1) or \ - (not (self.CP.flags & SubaruFlags.PREGLOBAL) and cp.vl["Dashlights"]["UNITS"] == 1): - ret.cruiseState.speed *= CV.MPH_TO_KPH - - ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1 - ret.doorOpen = any([cp.vl["BodyInfo"]["DOOR_OPEN_RR"], - cp.vl["BodyInfo"]["DOOR_OPEN_RL"], - cp.vl["BodyInfo"]["DOOR_OPEN_FR"], - cp.vl["BodyInfo"]["DOOR_OPEN_FL"]]) - ret.steerFaultPermanent = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1 - - if self.CP.flags & SubaruFlags.PREGLOBAL: - self.cruise_button = cp_cam.vl["ES_Distance"]["Cruise_Button"] - self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] - else: - ret.steerFaultTemporary = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 - ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 - ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 - ret.stockFcw = (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 1) or \ - (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 2) - - self.es_lkas_state_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) - cp_es_brake = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam - self.es_brake_msg = copy.copy(cp_es_brake.vl["ES_Brake"]) - cp_es_status = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam - - # TODO: Hybrid cars don't have ES_Distance, need a replacement - if not (self.CP.flags & SubaruFlags.HYBRID): - # 8 is known AEB, there are a few other values related to AEB we ignore - ret.stockAeb = (cp_es_distance.vl["ES_Brake"]["AEB_Status"] == 8) and \ - (cp_es_distance.vl["ES_Brake"]["Brake_Pressure"] != 0) - - self.es_status_msg = copy.copy(cp_es_status.vl["ES_Status"]) - self.cruise_control_msg = copy.copy(cp_cruise.vl["CruiseControl"]) - - if not (self.CP.flags & SubaruFlags.HYBRID): - self.es_distance_msg = copy.copy(cp_es_distance.vl["ES_Distance"]) - - self.es_dashstatus_msg = copy.copy(cp_cam.vl["ES_DashStatus"]) - if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: - self.es_infotainment_msg = copy.copy(cp_cam.vl["ES_Infotainment"]) - - return ret - - @staticmethod - def get_common_global_body_messages(CP): - messages = [ - ("Wheel_Speeds", 50), - ("Brake_Status", 50), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages.append(("CruiseControl", 20)) - - return messages - - @staticmethod - def get_common_global_es_messages(CP): - messages = [ - ("ES_Brake", 20), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages += [ - ("ES_Distance", 20), - ("ES_Status", 20) - ] - - return messages - - @staticmethod - def get_common_preglobal_body_messages(): - messages = [ - ("CruiseControl", 50), - ("Wheel_Speeds", 50), - ("Dash_State2", 1), - ] - - return messages - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("Dashlights", 10), - ("Steering_Torque", 50), - ("BodyInfo", 1), - ("Brake_Pedal", 50), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages += [ - ("Throttle", 100), - ("Transmission", 100) - ] - - if CP.enableBsm: - messages.append(("BSD_RCTA", 17)) - - if not (CP.flags & SubaruFlags.PREGLOBAL): - if not (CP.flags & SubaruFlags.GLOBAL_GEN2): - messages += CarState.get_common_global_body_messages(CP) - else: - messages += CarState.get_common_preglobal_body_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.main) - - @staticmethod - def get_cam_can_parser(CP): - if CP.flags & SubaruFlags.PREGLOBAL: - messages = [ - ("ES_DashStatus", 20), - ("ES_Distance", 20), - ] - else: - messages = [ - ("ES_DashStatus", 10), - ("ES_LKAS_State", 10), - ] - - if not (CP.flags & SubaruFlags.GLOBAL_GEN2): - messages += CarState.get_common_global_es_messages(CP) - - if CP.flags & SubaruFlags.SEND_INFOTAINMENT: - messages.append(("ES_Infotainment", 10)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.camera) - - @staticmethod - def get_body_can_parser(CP): - messages = [] - - if CP.flags & SubaruFlags.GLOBAL_GEN2: - messages += CarState.get_common_global_body_messages(CP) - messages += CarState.get_common_global_es_messages(CP) - - if CP.flags & SubaruFlags.HYBRID: - messages += [ - ("Throttle_Hybrid", 40), - ("Transmission", 100) - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.alt) - diff --git a/selfdrive/car/subaru/fingerprints.py b/selfdrive/car/subaru/fingerprints.py deleted file mode 100644 index 7f3ae73163e418..00000000000000 --- a/selfdrive/car/subaru/fingerprints.py +++ /dev/null @@ -1,563 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.SUBARU_ASCENT: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 \x19\x02\x00', - b'\xa5 !\x02\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x05\xc0\xd0\x00', - b'\x85\xc0\xd0\x00', - b'\x95\xc0\xd0\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00d\xb9\x00\x00\x00\x00', - b'\x00\x00d\xb9\x1f@ \x10', - b'\x00\x00e@\x00\x00\x00\x00', - b'\x00\x00e@\x1f@ $', - b"\x00\x00e~\x1f@ '", - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbb,\xa0t\x07', - b'\xd1,\xa0q\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x00>\xf0\x00\x00', - b'\x00\xfe\xf7\x00\x00', - b'\x01\xfe\xf7\x00\x00', - b'\x01\xfe\xf9\x00\x00', - b'\x01\xfe\xfa\x00\x00', - ], - }, - CAR.SUBARU_ASCENT_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 #\x03\x00', - ], - (Ecu.eps, 0x746, None): [ - b'%\xc0\xd0\x11', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x05!\x08\x1dK\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xe5,\xa0P\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\x04\xfe\xf3\x00\x00', - ], - }, - CAR.SUBARU_LEGACY: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x02\x01', - b'\xa1 \x02\x02', - b'\xa1 \x03\x03', - b'\xa1 \x04\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x9b\xc0\x11\x00', - b'\x9b\xc0\x11\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xde"a0\x07', - b'\xde,\xa0@\x07', - b'\xe2"aq\x07', - b'\xe2,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6\x05@\x00', - b'\xa5\xfe\xc7@\x00', - b'\xa7\xf6\x04@\x00', - b'\xa7\xfe\xc4@\x00', - ], - }, - CAR.SUBARU_IMPREZA: { - (Ecu.abs, 0x7b0, None): [ - b'z\x84\x19\x90\x00', - b'z\x94\x08\x90\x00', - b'z\x94\x08\x90\x01', - b'z\x94\x0c\x90\x00', - b'z\x94\x0c\x90\x01', - b'z\x94.\x90\x00', - b'z\x94?\x90\x00', - b'z\x9c\x19\x80\x01', - b'\xa2 \x185\x00', - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'\xa2 \x19`\x00', - ], - (Ecu.eps, 0x746, None): [ - b'z\xc0\x00\x00', - b'z\xc0\x04\x00', - b'z\xc0\x08\x00', - b'z\xc0\n\x00', - b'z\xc0\x0c\x00', - b'\x8a\xc0\x00\x00', - b'\x8a\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xf4\x00\x00\x00\x00', - b'\x00\x00c\xf4\x1f@ \x07', - b'\x00\x00d)\x00\x00\x00\x00', - b'\x00\x00d)\x1f@ \x07', - b'\x00\x00dd\x00\x00\x00\x00', - b'\x00\x00dd\x1f@ \x0e', - b'\x00\x00d\xb5\x1f@ \x0e', - b'\x00\x00d\xdc\x00\x00\x00\x00', - b'\x00\x00d\xdc\x1f@ \x0e', - b'\x00\x00e\x02\x1f@ \x14', - b'\x00\x00e\x1c\x00\x00\x00\x00', - b'\x00\x00e\x1c\x1f@ \x14', - b'\x00\x00e+\x00\x00\x00\x00', - b'\x00\x00e+\x1f@ \x14', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xaa\x00Bu\x07', - b'\xaa\x01bt\x07', - b'\xaa!`u\x07', - b'\xaa!au\x07', - b'\xaa!av\x07', - b'\xaa!aw\x07', - b'\xaa!dq\x07', - b'\xaa!ds\x07', - b'\xaa!dt\x07', - b'\xaaafs\x07', - b'\xbe!as\x07', - b'\xbe!at\x07', - b'\xbeacr\x07', - b'\xc5!`r\x07', - b'\xc5!`s\x07', - b'\xc5!ap\x07', - b'\xc5!ar\x07', - b'\xc5!as\x07', - b'\xc5!dr\x07', - b'\xc5!ds\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe3\xd0\x081\x00', - b'\xe3\xd5\x161\x00', - b'\xe3\xe5F1\x00', - b'\xe3\xf5\x06\x00\x00', - b'\xe3\xf5\x07\x00\x00', - b'\xe3\xf5C\x00\x00', - b'\xe3\xf5F\x00\x00', - b'\xe3\xf5G\x00\x00', - b'\xe4\xe5\x021\x00', - b'\xe4\xe5\x061\x00', - b'\xe4\xf5\x02\x00\x00', - b'\xe4\xf5\x07\x00\x00', - b'\xe5\xf5\x04\x00\x00', - b'\xe5\xf5$\x00\x00', - b'\xe5\xf5B\x00\x00', - ], - }, - CAR.SUBARU_IMPREZA_2020: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'\xa2 `\x00', - b'\xa2 !3\x00', - b'\xa2 !6\x00', - b'\xa2 !`\x00', - b'\xa2 !i\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\n\xc0\x04\x00', - b'\n\xc0\x04\x01', - b'\x9a\xc0\x00\x00', - b'\x9a\xc0\x04\x00', - b'\x9a\xc0\n\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eb\x1f@ "', - b'\x00\x00eq\x00\x00\x00\x00', - b'\x00\x00eq\x1f@ "', - b'\x00\x00e\x8f\x00\x00\x00\x00', - b'\x00\x00e\x8f\x1f@ )', - b'\x00\x00e\x92\x00\x00\x00\x00', - b'\x00\x00e\xa4\x00\x00\x00\x00', - b'\x00\x00e\xa4\x1f@ (', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xca!`0\x07', - b'\xca!`p\x07', - b'\xca!ap\x07', - b'\xca!f@\x07', - b'\xca!fp\x07', - b'\xcaacp\x07', - b'\xcc!`p\x07', - b'\xcc!fp\x07', - b'\xcc"f0\x07', - b'\xe6!`@\x07', - b'\xe6!fp\x07', - b'\xe6"f0\x07', - b'\xe6"fp\x07', - b'\xf3"f@\x07', - b'\xf3"fp\x07', - b'\xf3"fr\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe6\x15\x042\x00', - b'\xe6\xf5\x04\x00\x00', - b'\xe6\xf5$\x00\x00', - b'\xe6\xf5D0\x00', - b'\xe7\xf5\x04\x00\x00', - b'\xe7\xf5D0\x00', - b'\xe7\xf6B0\x00', - b'\xe9\xf5"\x00\x00', - b'\xe9\xf5B0\x00', - b'\xe9\xf6B0\x00', - b'\xe9\xf6F0\x00', - ], - }, - CAR.SUBARU_CROSSTREK_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x19e\x01', - b'\xa2 !e\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\n\xc2\x01\x00', - b'\x9a\xc2\x01\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00el\x1f@ #', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd7!`@\x07', - b'\xd7!`p\x07', - b'\xf4!`0\x07', - ], - }, - CAR.SUBARU_FORESTER: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x18\x14\x00', - b'\xa3 \x18&\x00', - b'\xa3 \x19\x14\x00', - b'\xa3 \x19&\x00', - b'\xa3 \x19h\x00', - b'\xa3 \x14\x00', - b'\xa3 \x14\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc0\x00\x00', - b'\x8d\xc0\x04\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e!\x00\x00\x00\x00', - b'\x00\x00e!\x1f@ \x11', - b'\x00\x00e^\x00\x00\x00\x00', - b'\x00\x00e^\x1f@ !', - b'\x00\x00e`\x00\x00\x00\x00', - b'\x00\x00e`\x1f@ ', - b'\x00\x00e\x97\x00\x00\x00\x00', - b'\x00\x00e\x97\x1f@ 0', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb6"`A\x07', - b'\xb6\xa2`A\x07', - b'\xcb"`@\x07', - b'\xcb"`p\x07', - b'\xcf"`0\x07', - b'\xcf"`p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1a\xe6B1\x00', - b'\x1a\xe6F1\x00', - b'\x1a\xf6B0\x00', - b'\x1a\xf6B`\x00', - b'\x1a\xf6F`\x00', - b'\x1a\xf6b0\x00', - b'\x1a\xf6b`\x00', - b'\x1a\xf6f`\x00', - ], - }, - CAR.SUBARU_FORESTER_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x19T\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc2\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eY\x1f@ !', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd2\xa1`r\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1b\xa7@a\x00', - ], - }, - CAR.SUBARU_FORESTER_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'm\x97\x14@', - b'}\x97\x14@', - ], - (Ecu.eps, 0x746, None): [ - b'm\xc0\x10\x00', - b'}\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xe9\x00\x00\x00\x00', - b'\x00\x00c\xe9\x1f@ \x03', - b'\x00\x00d5\x1f@ \t', - b'\x00\x00d\xd3\x1f@ \t', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa7"@0\x07', - b'\xa7"@p\x07', - b'\xa7)\xa0q\x07', - b'\xba"@@\x07', - b'\xba"@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1a\xf6F`\x00', - b'\xda\xf2`p\x00', - b'\xda\xf2`\x80\x00', - b'\xda\xfd\xe0\x80\x00', - b'\xdc\xf2@`\x00', - b'\xdc\xf2``\x00', - b'\xdc\xf2`\x80\x00', - b'\xdc\xf2`\x81\x00', - ], - }, - CAR.SUBARU_LEGACY_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'[\x97D\x00', - b'[\xba\xc4\x03', - b'k\x97D\x00', - b'k\x9aD\x00', - b'{\x97D\x00', - ], - (Ecu.eps, 0x746, None): [ - b'K\xb0\x00\x01', - b'[\xb0\x00\x01', - b'k\xb0\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa0"@q\x07', - b'\xa0+@p\x07', - b'\xab*@r\x07', - b'\xab+@p\x07', - b'\xb4"@0\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xf2\x00`\x00', - b'\xbe\xf2\x00p\x00', - b'\xbe\xfb\xc0p\x00', - b'\xbf\xf2\x00\x80\x00', - b'\xbf\xfb\xc0\x80\x00', - ], - }, - CAR.SUBARU_OUTBACK_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'[\xba\xac\x03', - b'[\xf7\xac\x00', - b'[\xf7\xac\x03', - b'[\xf7\xbc\x03', - b'k\x97\xac\x00', - b'k\x9a\xac\x00', - b'{\x97\xac\x00', - b'{\x9a\xac\x00', - ], - (Ecu.eps, 0x746, None): [ - b'K\xb0\x00\x00', - b'K\xb0\x00\x02', - b'[\xb0\x00\x00', - b'k\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\x90\x1f@\x10\x0e', - b'\x00\x00c\x94\x00\x00\x00\x00', - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\xd1\x1f@\x10\x17', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa0"@\x80\x07', - b'\xa0*@q\x07', - b'\xa0*@u\x07', - b'\xa0+@@\x07', - b'\xa0bAq\x07', - b'\xab"@@\x07', - b'\xab"@s\x07', - b'\xab*@@\x07', - b'\xab+@@\x07', - b'\xb4"@0\x07', - b'\xb4"@p\x07', - b'\xb4"@r\x07', - b'\xb4+@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xf2@`\x00', - b'\xbd\xf2@\x81\x00', - b'\xbd\xfb\xe0\x80\x00', - b'\xbe\xf2@p\x00', - b'\xbe\xf2@\x80\x00', - b'\xbe\xfb\xe0p\x00', - b'\xbf\xe2@\x80\x00', - b'\xbf\xf2@\x80\x00', - b'\xbf\xfb\xe0b\x00', - ], - }, - CAR.SUBARU_OUTBACK_PREGLOBAL_2018: { - (Ecu.abs, 0x7b0, None): [ - b'\x8b\x97\xac\x00', - b'\x8b\x97\xbc\x00', - b'\x8b\x99\xac\x00', - b'\x8b\x9a\xac\x00', - b'\x9b\x97\xac\x00', - b'\x9b\x97\xbe\x10', - b'\x9b\x9a\xac\x00', - ], - (Ecu.eps, 0x746, None): [ - b'{\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00df\x1f@ \n', - b'\x00\x00d\x95\x00\x00\x00\x00', - b'\x00\x00d\x95\x1f@ \x0f', - b'\x00\x00d\xfe\x00\x00\x00\x00', - b'\x00\x00d\xfe\x1f@ \x15', - b'\x00\x00e\x19\x1f@ \x15', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb5"@P\x07', - b'\xb5"@p\x07', - b'\xb5+@@\x07', - b'\xb5b@1\x07', - b'\xb5q\xe0@\x07', - b'\xc4"@0\x07', - b'\xc4+@0\x07', - b'\xc4b@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbb\xf2@`\x00', - b'\xbb\xfb\xe0`\x00', - b'\xbc\xaf\xe0`\x00', - b'\xbc\xe2@\x80\x00', - b'\xbc\xf2@\x80\x00', - b'\xbc\xf2@\x81\x00', - b'\xbc\xfb\xe0`\x00', - b'\xbc\xfb\xe0\x80\x00', - ], - }, - CAR.SUBARU_OUTBACK: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x06\x00', - b'\xa1 \x06\x01', - b'\xa1 \x06\x02', - b'\xa1 \x07\x00', - b'\xa1 \x07\x02', - b'\xa1 \x07\x03', - b'\xa1 \x08\x00', - b'\xa1 \x08\x01', - b'\xa1 \x08\x02', - b'\xa1 "\t\x00', - b'\xa1 "\t\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x1b\xc0\x10\x00', - b'\x9b\xc0\x10\x00', - b'\x9b\xc0\x10\x02', - b'\x9b\xc0 \x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', - b'\x00\x00eJ\x00\x1f@ \x19\x00', - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - b'\x00\x00e\x9a\x00\x1f@ 1\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbc"`@\x07', - b'\xbc"`q\x07', - b'\xbc,\xa0q\x07', - b'\xbc,\xa0u\x07', - b'\xde"`0\x07', - b'\xde,\xa0@\x07', - b'\xe2"`0\x07', - b'\xe2"`p\x07', - b'\xe2"`q\x07', - b'\xe3,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6D@\x00', - b'\xa5\xfe\xf6@\x00', - b'\xa5\xfe\xf7@\x00', - b'\xa5\xfe\xf8@\x00', - b'\xa7\x8e\xf40\x00', - b'\xa7\xf6D@\x00', - b'\xa7\xfe\xf4@\x00', - ], - }, - CAR.SUBARU_FORESTER_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 !v\x00', - b'\xa3 !x\x00', - b'\xa3 "v\x00', - b'\xa3 "x\x00', - ], - (Ecu.eps, 0x746, None): [ - b'-\xc0\x040', - b'-\xc0%0', - b'=\xc0%\x02', - b'=\xc04\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x04!\x01\x1eD\x07!\x00\x04,', - b'\x04!\x08\x01.\x07!\x08\x022', - b'\r!\x08\x017\n!\x08\x003', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd5"`0\x07', - b'\xd5"a0\x07', - b'\xf1"`q\x07', - b'\xf1"aq\x07', - b'\xfa"ap\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1d\x86B0\x00', - b'\x1d\xf6B0\x00', - b'\x1e\x86B0\x00', - b'\x1e\x86F0\x00', - b'\x1e\xf6D0\x00', - ], - }, - CAR.SUBARU_OUTBACK_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 #\x14\x00', - b'\xa1 #\x17\x00', - ], - (Ecu.eps, 0x746, None): [ - b'+\xc0\x10\x11\x00', - b'+\xc0\x12\x11\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\t!\x08\x046\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xed,\xa0q\x07', - b'\xed,\xa2q\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\xa8\x8e\xf41\x00', - b'\xa8\xfe\xf41\x00', - ], - }, -} diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py deleted file mode 100644 index 0ea71e812f4c84..00000000000000 --- a/selfdrive/car/subaru/interface.py +++ /dev/null @@ -1,111 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.disable_ecu import disable_ecu -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.subaru.values import CAR, GLOBAL_ES_ADDR, SubaruFlags - - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): - ret.carName = "subaru" - ret.radarUnavailable = True - # for HYBRID CARS to be upstreamed, we need: - # - replacement for ES_Distance so we can cancel the cruise control - # - to find the Cruise_Activated bit from the car - # - proper panda safety setup (use the correct cruise_activated bit, throttle from Throttle_Hybrid, etc) - ret.dashcamOnly = bool(ret.flags & (SubaruFlags.PREGLOBAL | SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.autoResumeSng = False - - # Detect infotainment message sent from the camera - if not (ret.flags & SubaruFlags.PREGLOBAL) and 0x323 in fingerprint[2]: - ret.flags |= SubaruFlags.SEND_INFOTAINMENT.value - - if ret.flags & SubaruFlags.PREGLOBAL: - ret.enableBsm = 0x25c in fingerprint[0] - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaruPreglobal)] - else: - ret.enableBsm = 0x228 in fingerprint[0] - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaru)] - if ret.flags & SubaruFlags.GLOBAL_GEN2: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_GEN2 - - ret.steerLimitTimer = 0.4 - ret.steerActuatorDelay = 0.1 - - if ret.flags & SubaruFlags.LKAS_ANGLE: - ret.steerControlType = car.CarParams.SteerControlType.angle - else: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate in (CAR.SUBARU_ASCENT, CAR.SUBARU_ASCENT_2023): - ret.steerActuatorDelay = 0.3 # end-to-end angle controller - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00003 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] - - elif candidate == CAR.SUBARU_IMPREZA: - ret.steerActuatorDelay = 0.4 # end-to-end angle controller - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] - - elif candidate == CAR.SUBARU_IMPREZA_2020: - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] - - elif candidate == CAR.SUBARU_CROSSTREK_HYBRID: - ret.steerActuatorDelay = 0.1 - - elif candidate in (CAR.SUBARU_FORESTER, CAR.SUBARU_FORESTER_2022, CAR.SUBARU_FORESTER_HYBRID): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.000038 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] - - elif candidate in (CAR.SUBARU_OUTBACK, CAR.SUBARU_LEGACY, CAR.SUBARU_OUTBACK_2023): - ret.steerActuatorDelay = 0.1 - - elif candidate in (CAR.SUBARU_FORESTER_PREGLOBAL, CAR.SUBARU_OUTBACK_PREGLOBAL_2018): - ret.safetyConfigs[0].safetyParam = Panda.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE # Outback 2018-2019 and Forester have reversed driver torque signal - - elif candidate == CAR.SUBARU_LEGACY_PREGLOBAL: - ret.steerActuatorDelay = 0.15 - - elif candidate == CAR.SUBARU_OUTBACK_PREGLOBAL: - pass - else: - raise ValueError(f"unknown car: {candidate}") - - ret.experimentalLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | - SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - - if ret.flags & SubaruFlags.GLOBAL_GEN2 and ret.openpilotLongitudinalControl: - ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value - - if ret.openpilotLongitudinalControl: - ret.stoppingControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_LONG - - return ret - - # returns a car.CarState - def _update(self, c): - - ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - - ret.events = self.create_common_events(ret).to_msg() - - return ret - - @staticmethod - def init(CP, can_recv, can_send): - if CP.flags & SubaruFlags.DISABLE_EYESIGHT: - disable_ecu(can_recv, can_send, bus=2, addr=GLOBAL_ES_ADDR, com_cont_req=b'\x28\x03\x01') diff --git a/selfdrive/car/subaru/radar_interface.py b/selfdrive/car/subaru/radar_interface.py deleted file mode 100644 index e654bd61fd4afd..00000000000000 --- a/selfdrive/car/subaru/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py deleted file mode 100644 index 41bd177ff2de76..00000000000000 --- a/selfdrive/car/subaru/subarucan.py +++ /dev/null @@ -1,321 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.values import CanBus - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -def create_steering_control(packer, apply_steer, steer_req): - values = { - "LKAS_Output": apply_steer, - "LKAS_Request": steer_req, - "SET_1": 1 - } - return packer.make_can_msg("ES_LKAS", 0, values) - - -def create_steering_control_angle(packer, apply_steer, steer_req): - values = { - "LKAS_Output": apply_steer, - "LKAS_Request": steer_req, - "SET_3": 3 - } - return packer.make_can_msg("ES_LKAS_ANGLE", 0, values) - - -def create_steering_status(packer): - return packer.make_can_msg("ES_LKAS_State", 0, {}) - -def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long_enabled = False, brake_cmd = False, cruise_throttle = 0): - values = {s: es_distance_msg[s] for s in [ - "CHECKSUM", - "Signal1", - "Cruise_Fault", - "Cruise_Throttle", - "Signal2", - "Car_Follow", - "Low_Speed_Follow", - "Cruise_Soft_Disable", - "Signal7", - "Cruise_Brake_Active", - "Distance_Swap", - "Cruise_EPB", - "Signal4", - "Close_Distance", - "Signal5", - "Cruise_Cancel", - "Cruise_Set", - "Cruise_Resume", - "Signal6", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_Throttle"] = cruise_throttle - - # Do not disable openpilot on Eyesight Soft Disable, if openpilot is controlling long - values["Cruise_Soft_Disable"] = 0 - values["Cruise_Fault"] = 0 - - values["Cruise_Brake_Active"] = brake_cmd - - if pcm_cancel_cmd: - values["Cruise_Cancel"] = 1 - values["Cruise_Throttle"] = 1818 # inactive throttle - - return packer.make_can_msg("ES_Distance", bus, values) - - -def create_es_lkas_state(packer, frame, es_lkas_state_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): - values = {s: es_lkas_state_msg[s] for s in [ - "CHECKSUM", - "LKAS_Alert_Msg", - "Signal1", - "LKAS_ACTIVE", - "LKAS_Dash_State", - "Signal2", - "Backward_Speed_Limit_Menu", - "LKAS_Left_Line_Enable", - "LKAS_Left_Line_Light_Blink", - "LKAS_Right_Line_Enable", - "LKAS_Right_Line_Light_Blink", - "LKAS_Left_Line_Visible", - "LKAS_Right_Line_Visible", - "LKAS_Alert", - "Signal3", - ]} - - values["COUNTER"] = frame % 0x10 - - # Filter the stock LKAS "Keep hands on wheel" alert - if values["LKAS_Alert_Msg"] == 1: - values["LKAS_Alert_Msg"] = 0 - - # Filter the stock LKAS sending an audible alert when it turns off LKAS - if values["LKAS_Alert"] == 27: - values["LKAS_Alert"] = 0 - - # Filter the stock LKAS sending an audible alert when "Keep hands on wheel" alert is active (2020+ models) - if values["LKAS_Alert"] == 28 and values["LKAS_Alert_Msg"] == 7: - values["LKAS_Alert"] = 0 - - # Filter the stock LKAS sending an audible alert when "Keep hands on wheel OFF" alert is active (2020+ models) - if values["LKAS_Alert"] == 30: - values["LKAS_Alert"] = 0 - - # Filter the stock LKAS sending "Keep hands on wheel OFF" alert (2020+ models) - if values["LKAS_Alert_Msg"] == 7: - values["LKAS_Alert_Msg"] = 0 - - # Show Keep hands on wheel alert for openpilot steerRequired alert - if visual_alert == VisualAlert.steerRequired: - values["LKAS_Alert_Msg"] = 1 - - # Ensure we don't overwrite potentially more important alerts from stock (e.g. FCW) - if visual_alert == VisualAlert.ldw and values["LKAS_Alert"] == 0: - if left_lane_depart: - values["LKAS_Alert"] = 12 # Left lane departure dash alert - elif right_lane_depart: - values["LKAS_Alert"] = 11 # Right lane departure dash alert - - if enabled: - values["LKAS_ACTIVE"] = 1 # Show LKAS lane lines - values["LKAS_Dash_State"] = 2 # Green enabled indicator - else: - values["LKAS_Dash_State"] = 0 # LKAS Not enabled - - values["LKAS_Left_Line_Visible"] = int(left_line) - values["LKAS_Right_Line_Visible"] = int(right_line) - - return packer.make_can_msg("ES_LKAS_State", CanBus.main, values) - -def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, long_active, lead_visible): - values = {s: dashstatus_msg[s] for s in [ - "CHECKSUM", - "PCB_Off", - "LDW_Off", - "Signal1", - "Cruise_State_Msg", - "LKAS_State_Msg", - "Signal2", - "Cruise_Soft_Disable", - "Cruise_Status_Msg", - "Signal3", - "Cruise_Distance", - "Signal4", - "Conventional_Cruise", - "Signal5", - "Cruise_Disengaged", - "Cruise_Activated", - "Signal6", - "Cruise_Set_Speed", - "Cruise_Fault", - "Cruise_On", - "Display_Own_Car", - "Brake_Lights", - "Car_Follow", - "Signal7", - "Far_Distance", - "Cruise_State", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_State"] = 0 - values["Cruise_Activated"] = enabled - values["Cruise_Disengaged"] = 0 - values["Car_Follow"] = int(lead_visible) - - values["PCB_Off"] = 1 # AEB is not presevered, so show the PCB_Off on dash - values["LDW_Off"] = 0 - values["Cruise_Fault"] = 0 - - # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts - if values["LKAS_State_Msg"] in (2, 3): - values["LKAS_State_Msg"] = 0 - - return packer.make_can_msg("ES_DashStatus", CanBus.main, values) - -def create_es_brake(packer, frame, es_brake_msg, long_enabled, long_active, brake_value): - values = {s: es_brake_msg[s] for s in [ - "CHECKSUM", - "Signal1", - "Brake_Pressure", - "AEB_Status", - "Cruise_Brake_Lights", - "Cruise_Brake_Fault", - "Cruise_Brake_Active", - "Cruise_Activated", - "Signal3", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_Brake_Fault"] = 0 - values["Cruise_Activated"] = long_active - - values["Brake_Pressure"] = brake_value - - values["Cruise_Brake_Active"] = brake_value > 0 - values["Cruise_Brake_Lights"] = brake_value >= 70 - - return packer.make_can_msg("ES_Brake", CanBus.main, values) - -def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cruise_rpm): - values = {s: es_status_msg[s] for s in [ - "CHECKSUM", - "Signal1", - "Cruise_Fault", - "Cruise_RPM", - "Cruise_Activated", - "Brake_Lights", - "Cruise_Hold", - "Signal3", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_RPM"] = cruise_rpm - values["Cruise_Fault"] = 0 - - values["Cruise_Activated"] = long_active - - return packer.make_can_msg("ES_Status", CanBus.main, values) - - -def create_es_infotainment(packer, frame, es_infotainment_msg, visual_alert): - # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts - values = {s: es_infotainment_msg[s] for s in [ - "CHECKSUM", - "LKAS_State_Infotainment", - "LKAS_Blue_Lines", - "Signal1", - "Signal2", - ]} - - values["COUNTER"] = frame % 0x10 - - if values["LKAS_State_Infotainment"] in (3, 4): - values["LKAS_State_Infotainment"] = 0 - - # Show Keep hands on wheel alert for openpilot steerRequired alert - if visual_alert == VisualAlert.steerRequired: - values["LKAS_State_Infotainment"] = 3 - - # Show Obstacle Detected for fcw - if visual_alert == VisualAlert.fcw: - values["LKAS_State_Infotainment"] = 2 - - return packer.make_can_msg("ES_Infotainment", CanBus.main, values) - - -def create_es_highbeamassist(packer): - values = { - "HBA_Available": False, - } - - return packer.make_can_msg("ES_HighBeamAssist", CanBus.main, values) - - -def create_es_static_1(packer): - values = { - "SET_3": 3, - } - - return packer.make_can_msg("ES_STATIC_1", CanBus.main, values) - - -def create_es_static_2(packer): - values = { - "SET_3": 3, - } - - return packer.make_can_msg("ES_STATIC_2", CanBus.main, values) - - -# *** Subaru Pre-global *** - -def subaru_preglobal_checksum(packer, values, addr, checksum_byte=7): - dat = packer.make_can_msg(addr, 0, values)[1] - return (sum(dat[:checksum_byte]) + sum(dat[checksum_byte+1:])) % 256 - - -def create_preglobal_steering_control(packer, frame, apply_steer, steer_req): - values = { - "COUNTER": frame % 0x08, - "LKAS_Command": apply_steer, - "LKAS_Active": steer_req, - } - values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_LKAS") - - return packer.make_can_msg("ES_LKAS", CanBus.main, values) - - -def create_preglobal_es_distance(packer, cruise_button, es_distance_msg): - values = {s: es_distance_msg[s] for s in [ - "Cruise_Throttle", - "Signal1", - "Car_Follow", - "Signal2", - "Cruise_Brake_Active", - "Distance_Swap", - "Standstill", - "Signal3", - "Close_Distance", - "Signal4", - "Standstill_2", - "Cruise_Fault", - "Signal5", - "COUNTER", - "Signal6", - "Cruise_Button", - "Signal7", - ]} - - values["Cruise_Button"] = cruise_button - values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_Distance") - - return packer.make_can_msg("ES_Distance", CanBus.main, values) diff --git a/selfdrive/car/subaru/tests/test_subaru.py b/selfdrive/car/subaru/tests/test_subaru.py deleted file mode 100644 index 33040442b69778..00000000000000 --- a/selfdrive/car/subaru/tests/test_subaru.py +++ /dev/null @@ -1,16 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -class TestSubaruFingerprint: - def test_fw_version_format(self): - for platform, fws_per_ecu in FW_VERSIONS.items(): - for (ecu, _, _), fws in fws_per_ecu.items(): - fw_size = len(fws[0]) - for fw in fws: - assert len(fw) == fw_size, f"{platform} {ecu}: {len(fw)} {fw_size}" - diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py deleted file mode 100644 index dcbea1979fd227..00000000000000 --- a/selfdrive/car/subaru/values.py +++ /dev/null @@ -1,275 +0,0 @@ -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Tool, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - def __init__(self, CP): - self.STEER_STEP = 2 # how often we update the steer cmd - self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max - self.STEER_DELTA_DOWN = 70 # torque decrease per refresh - self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting - self.STEER_DRIVER_MULTIPLIER = 50 # weight driver torque heavily - self.STEER_DRIVER_FACTOR = 1 # from dbc - - if CP.flags & SubaruFlags.GLOBAL_GEN2: - self.STEER_MAX = 1000 - self.STEER_DELTA_UP = 40 - self.STEER_DELTA_DOWN = 40 - elif CP.carFingerprint == CAR.SUBARU_IMPREZA_2020: - self.STEER_MAX = 1439 - else: - self.STEER_MAX = 2047 - - THROTTLE_MIN = 808 - THROTTLE_MAX = 3400 - - THROTTLE_INACTIVE = 1818 # corresponds to zero acceleration - THROTTLE_ENGINE_BRAKE = 808 # while braking, eyesight sets throttle to this, probably for engine braking - - BRAKE_MIN = 0 - BRAKE_MAX = 600 # about -3.5m/s2 from testing - - RPM_MIN = 0 - RPM_MAX = 3600 - - RPM_INACTIVE = 600 # a good base rpm for zero acceleration - - THROTTLE_LOOKUP_BP = [0, 2] - THROTTLE_LOOKUP_V = [THROTTLE_INACTIVE, THROTTLE_MAX] - - RPM_LOOKUP_BP = [0, 2] - RPM_LOOKUP_V = [RPM_INACTIVE, RPM_MAX] - - BRAKE_LOOKUP_BP = [-3.5, 0] - BRAKE_LOOKUP_V = [BRAKE_MAX, BRAKE_MIN] - - -class SubaruFlags(IntFlag): - # Detected flags - SEND_INFOTAINMENT = 1 - DISABLE_EYESIGHT = 2 - - # Static flags - GLOBAL_GEN2 = 4 - - # Cars that temporarily fault when steering angle rate is greater than some threshold. - # Appears to be all torque-based cars produced around 2019 - present - STEER_RATE_LIMITED = 8 - PREGLOBAL = 16 - HYBRID = 32 - LKAS_ANGLE = 64 - - -GLOBAL_ES_ADDR = 0x787 -GEN2_ES_BUTTONS_DID = b'\x11\x30' - - -class CanBus: - main = 0 - alt = 1 - camera = 2 - - -class Footnote(Enum): - GLOBAL = CarFootnote( - "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", - Column.PACKAGE) - EXP_LONG = CarFootnote( - "Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.", - Column.LONGITUDINAL) - - -@dataclass -class SubaruCarDocs(CarDocs): - package: str = "EyeSight Driver Assistance" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.subaru_a])) - footnotes: list[Enum] = field(default_factory=lambda: [Footnote.GLOBAL]) - - def init_make(self, CP: car.CarParams): - self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) - - if CP.experimentalLongitudinalAvailable: - self.footnotes.append(Footnote.EXP_LONG) - - -@dataclass -class SubaruPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('subaru_global_2017_generated', None)) - - def init(self): - if self.flags & SubaruFlags.HYBRID: - self.dbc_dict = dbc_dict('subaru_global_2020_hybrid_generated', None) - - -@dataclass -class SubaruGen2PlatformConfig(SubaruPlatformConfig): - def init(self): - super().init() - self.flags |= SubaruFlags.GLOBAL_GEN2 - if not (self.flags & SubaruFlags.LKAS_ANGLE): - self.flags |= SubaruFlags.STEER_RATE_LIMITED - - -class CAR(Platforms): - # Global platform - SUBARU_ASCENT = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Ascent 2019-21", "All")], - CarSpecs(mass=2031, wheelbase=2.89, steerRatio=13.5), - ) - SUBARU_OUTBACK = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Outback 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), - ) - SUBARU_LEGACY = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Legacy 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], - SUBARU_OUTBACK.specs, - ) - SUBARU_IMPREZA = SubaruPlatformConfig( - [ - SubaruCarDocs("Subaru Impreza 2017-19"), - SubaruCarDocs("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - SubaruCarDocs("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - ], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=15), - ) - SUBARU_IMPREZA_2020 = SubaruPlatformConfig( - [ - SubaruCarDocs("Subaru Impreza 2020-22"), - SubaruCarDocs("Subaru Crosstrek 2020-23"), - SubaruCarDocs("Subaru XV 2020-21"), - ], - CarSpecs(mass=1480, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.STEER_RATE_LIMITED, - ) - # TODO: is there an XV and Impreza too? - SUBARU_CROSSTREK_HYBRID = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Crosstrek Hybrid 2020", car_parts=CarParts.common([CarHarness.subaru_b]))], - CarSpecs(mass=1668, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.HYBRID, - ) - SUBARU_FORESTER = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2019-21", "All")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.STEER_RATE_LIMITED, - ) - SUBARU_FORESTER_HYBRID = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester Hybrid 2020")], - SUBARU_FORESTER.specs, - flags=SubaruFlags.HYBRID, - ) - # Pre-global - SUBARU_FORESTER_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2017-18")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=20), - dbc_dict('subaru_forester_2017_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_LEGACY_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Legacy 2015-18")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=12.5), - dbc_dict('subaru_outback_2015_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_OUTBACK_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Outback 2015-17")], - SUBARU_FORESTER_PREGLOBAL.specs, - dbc_dict('subaru_outback_2015_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_OUTBACK_PREGLOBAL_2018 = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Outback 2018-19")], - SUBARU_FORESTER_PREGLOBAL.specs, - dbc_dict('subaru_outback_2019_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - # Angle LKAS - SUBARU_FORESTER_2022 = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2022-24", "All", car_parts=CarParts.common([CarHarness.subaru_c]))], - SUBARU_FORESTER.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - SUBARU_OUTBACK_2023 = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Outback 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], - SUBARU_OUTBACK.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - SUBARU_ASCENT_2023 = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Ascent 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], - SUBARU_ASCENT.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - - -SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) - -# The EyeSight ECU takes 10s to respond to SUBARU_VERSION_REQUEST properly, -# log this alternate manufacturer-specific query -SUBARU_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) -SUBARU_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf100) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - logging=True, - ), - # Non-OBD requests - # Some Eyesight modules fail on TESTER_PRESENT_REQUEST - # TODO: check if this resolves the fingerprinting issue for the 2023 Ascent and other new Subaru cars - Request( - [SUBARU_VERSION_REQUEST], - [SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - ), - Request( - [SUBARU_ALT_VERSION_REQUEST], - [SUBARU_ALT_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - logging=True, - ), - Request( - [StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - logging=True, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - bus=0, - ), - # GEN2 powertrain bus query - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - bus=1, - obd_multiplexing=False, - ), - ], - # We don't get the EPS from non-OBD queries on GEN2 cars. Note that we still attempt to match when it exists - non_essential_ecus={ - Ecu.eps: list(CAR.with_flags(SubaruFlags.GLOBAL_GEN2)), - } -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/tesla/__init__.py b/selfdrive/car/tesla/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/tesla/carcontroller.py b/selfdrive/car/tesla/carcontroller.py deleted file mode 100644 index ed81fd0c50889d..00000000000000 --- a/selfdrive/car/tesla/carcontroller.py +++ /dev/null @@ -1,66 +0,0 @@ -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.helpers import clip -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.tesla.teslacan import TeslaCAN -from openpilot.selfdrive.car.tesla.values import DBC, CANBUS, CarControllerParams - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.apply_angle_last = 0 - self.packer = CANPacker(dbc_name) - self.pt_packer = CANPacker(DBC[CP.carFingerprint]['pt']) - self.tesla_can = TeslaCAN(self.packer, self.pt_packer) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - # Temp disable steering on a hands_on_fault, and allow for user override - hands_on_fault = CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3 - lkas_enabled = CC.latActive and not hands_on_fault - - if self.frame % 2 == 0: - if lkas_enabled: - # Angular rate limit based on speed - apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo, CarControllerParams) - - # To not fault the EPS - apply_angle = clip(apply_angle, CS.out.steeringAngleDeg - 20, CS.out.steeringAngleDeg + 20) - else: - apply_angle = CS.out.steeringAngleDeg - - self.apply_angle_last = apply_angle - can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, (self.frame // 2) % 16)) - - # Longitudinal control (in sync with stock message, about 40Hz) - if self.CP.openpilotLongitudinalControl: - target_accel = actuators.accel - target_speed = max(CS.out.vEgo + (target_accel * CarControllerParams.ACCEL_TO_SPEED_MULTIPLIER), 0) - max_accel = 0 if target_accel < 0 else target_accel - min_accel = 0 if target_accel > 0 else target_accel - - while len(CS.das_control_counters) > 0: - can_sends.extend(self.tesla_can.create_longitudinal_commands(CS.acc_state, target_speed, min_accel, max_accel, CS.das_control_counters.popleft())) - - # Cancel on user steering override, since there is no steering torque blending - if hands_on_fault: - pcm_cancel_cmd = True - - if self.frame % 10 == 0 and pcm_cancel_cmd: - # Spam every possible counter value, otherwise it might not be accepted - for counter in range(16): - can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.chassis, counter)) - can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.autopilot_chassis, counter)) - - # TODO: HUD control - - new_actuators = actuators.as_builder() - new_actuators.steeringAngleDeg = self.apply_angle_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/tesla/carstate.py b/selfdrive/car/tesla/carstate.py deleted file mode 100644 index 5aa21cbc7cd009..00000000000000 --- a/selfdrive/car/tesla/carstate.py +++ /dev/null @@ -1,139 +0,0 @@ -import copy -from collections import deque -from cereal import car -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS, GEAR_MAP, DOORS, BUTTONS -from openpilot.selfdrive.car.interfaces import CarStateBase - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.button_states = {button.event_type: False for button in BUTTONS} - self.can_define = CANDefine(DBC[CP.carFingerprint]['chassis']) - - # Needed by carcontroller - self.msg_stw_actn_req = None - self.hands_on_level = 0 - self.steer_warning = None - self.acc_state = 0 - self.das_control_counters = deque(maxlen=32) - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - # Vehicle speed - ret.vEgoRaw = cp.vl["ESP_B"]["ESP_vehicleSpeed"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = (ret.vEgo < 0.1) - - # Gas pedal - ret.gas = cp.vl["DI_torque1"]["DI_pedalPos"] / 100.0 - ret.gasPressed = (ret.gas > 0) - - # Brake pedal - ret.brake = 0 - ret.brakePressed = bool(cp.vl["BrakeMessage"]["driverBrakeStatus"] != 1) - - # Steering wheel - epas_status = cp_cam.vl["EPAS3P_sysStatus"] if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN else cp.vl["EPAS_sysStatus"] - - self.hands_on_level = epas_status["EPAS_handsOnLevel"] - self.steer_warning = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacErrorCode"].get(int(epas_status["EPAS_eacErrorCode"]), None) - steer_status = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacStatus"].get(int(epas_status["EPAS_eacStatus"]), None) - - ret.steeringAngleDeg = -epas_status["EPAS_internalSAS"] - ret.steeringRateDeg = -cp.vl["STW_ANGLHP_STAT"]["StW_AnglHP_Spd"] # This is from a different angle sensor, and at different rate - ret.steeringTorque = -epas_status["EPAS_torsionBarTorque"] - ret.steeringPressed = (self.hands_on_level > 0) - ret.steerFaultPermanent = steer_status == "EAC_FAULT" - ret.steerFaultTemporary = (self.steer_warning not in ("EAC_ERROR_IDLE", "EAC_ERROR_HANDS_ON")) - - # Cruise state - cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) - speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) - - acc_enabled = (cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL")) - - ret.cruiseState.enabled = acc_enabled - if speed_units == "KPH": - ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS - elif speed_units == "MPH": - ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.MPH_TO_MS - ret.cruiseState.available = ((cruise_state == "STANDBY") or ret.cruiseState.enabled) - ret.cruiseState.standstill = False # This needs to be false, since we can resume from stop without sending anything special - - # Gear - ret.gearShifter = GEAR_MAP[self.can_define.dv["DI_torque2"]["DI_gear"].get(int(cp.vl["DI_torque2"]["DI_gear"]), "DI_GEAR_INVALID")] - - # Buttons - buttonEvents = [] - for button in BUTTONS: - state = (cp.vl[button.can_addr][button.can_msg] in button.values) - if self.button_states[button.event_type] != state: - event = car.CarState.ButtonEvent.new_message() - event.type = button.event_type - event.pressed = state - buttonEvents.append(event) - self.button_states[button.event_type] = state - ret.buttonEvents = buttonEvents - - # Doors - ret.doorOpen = any((self.can_define.dv["GTW_carState"][door].get(int(cp.vl["GTW_carState"][door]), "OPEN") == "OPEN") for door in DOORS) - - # Blinkers - ret.leftBlinker = (cp.vl["GTW_carState"]["BC_indicatorLStatus"] == 1) - ret.rightBlinker = (cp.vl["GTW_carState"]["BC_indicatorRStatus"] == 1) - - # Seatbelt - if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - ret.seatbeltUnlatched = (cp.vl["DriverSeat"]["buckleStatus"] != 1) - else: - ret.seatbeltUnlatched = (cp.vl["SDM1"]["SDM_bcklDrivStatus"] != 1) - - # TODO: blindspot - - # AEB - ret.stockAeb = (cp_cam.vl["DAS_control"]["DAS_aebEvent"] == 1) - - # Messages needed by carcontroller - self.msg_stw_actn_req = copy.copy(cp.vl["STW_ACTN_RQ"]) - self.acc_state = cp_cam.vl["DAS_control"]["DAS_accState"] - self.das_control_counters.extend(cp_cam.vl_all["DAS_control"]["DAS_controlCounter"]) - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("ESP_B", 50), - ("DI_torque1", 100), - ("DI_torque2", 100), - ("STW_ANGLHP_STAT", 100), - ("EPAS_sysStatus", 25), - ("DI_state", 10), - ("STW_ACTN_RQ", 10), - ("GTW_carState", 10), - ("BrakeMessage", 50), - ] - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages.append(("DriverSeat", 20)) - else: - messages.append(("SDM1", 10)) - - return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.chassis) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - # sig_address, frequency - ("DAS_control", 40), - ] - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages.append(("EPAS3P_sysStatus", 100)) - - return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.autopilot_chassis) diff --git a/selfdrive/car/tesla/fingerprints.py b/selfdrive/car/tesla/fingerprints.py deleted file mode 100644 index 68c50a62ed05fc..00000000000000 --- a/selfdrive/car/tesla/fingerprints.py +++ /dev/null @@ -1,32 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.tesla.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.TESLA_AP2_MODELS: { - (Ecu.adas, 0x649, None): [ - b'\x01\x00\x8b\x07\x01\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x11', - ], - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00W\x00\x00\x00\x07\x00\x00\x00\x00\x08\x01\x00\x00\x00\x07\xff\xfe', - ], - (Ecu.eps, 0x730, None): [ - b'\x10#\x01', - ], - }, - CAR.TESLA_MODELS_RAVEN: { - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00\x99\x02\x01\x00\x10\x00\x00AP8.3.03\x00\x10', - ], - (Ecu.eps, 0x730, None): [ - b'SX_0.0.0 (99),SR013.7', - ], - }, -} diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py deleted file mode 100755 index deb0e00230a1b8..00000000000000 --- a/selfdrive/car/tesla/interface.py +++ /dev/null @@ -1,47 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.tesla.values import CANBUS, CAR -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "tesla" - - # There is no safe way to do steer blending with user torque, - # so the steering behaves like autopilot. This is not - # how openpilot should be, hence dashcamOnly - ret.dashcamOnly = True - - ret.steerControlType = car.CarParams.SteerControlType.angle - - ret.longitudinalActuatorDelay = 0.5 # s - ret.radarTimeStep = (1.0 / 8) # 8Hz - - # Check if we have messages on an auxiliary panda, and that 0x2bf (DAS_control) is present on the AP powertrain bus - # If so, we assume that it is connected to the longitudinal harness. - flags = (Panda.FLAG_TESLA_RAVEN if candidate == CAR.TESLA_MODELS_RAVEN else 0) - if (CANBUS.autopilot_powertrain in fingerprint.keys()) and (0x2bf in fingerprint[CANBUS.autopilot_powertrain].keys()): - ret.openpilotLongitudinalControl = True - flags |= Panda.FLAG_TESLA_LONG_CONTROL - ret.safetyConfigs = [ - get_safety_config(car.CarParams.SafetyModel.tesla, flags), - get_safety_config(car.CarParams.SafetyModel.tesla, flags | Panda.FLAG_TESLA_POWERTRAIN), - ] - else: - ret.openpilotLongitudinalControl = False - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.tesla, flags)] - - ret.steerLimitTimer = 1.0 - ret.steerActuatorDelay = 0.25 - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.events = self.create_common_events(ret).to_msg() - - return ret diff --git a/selfdrive/car/tesla/radar_interface.py b/selfdrive/car/tesla/radar_interface.py deleted file mode 100755 index 1684e42e7f593d..00000000000000 --- a/selfdrive/car/tesla/radar_interface.py +++ /dev/null @@ -1,90 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages = [('RadarStatus', 16)] - self.num_points = 40 - self.trigger_msg = 1119 - else: - messages = [('TeslaRadarSguInfo', 10)] - self.num_points = 32 - self.trigger_msg = 878 - - for i in range(self.num_points): - messages.extend([ - (f'RadarPoint{i}_A', 16), - (f'RadarPoint{i}_B', 16), - ]) - - self.rcp = CANParser(DBC[CP.carFingerprint]['radar'], messages, CANBUS.radar) - self.updated_messages = set() - self.track_id = 0 - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - values = self.rcp.update_strings(can_strings) - self.updated_messages.update(values) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - - # Errors - errors = [] - if not self.rcp.can_valid: - errors.append('canError') - - if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - radar_status = self.rcp.vl['RadarStatus'] - if radar_status['sensorBlocked'] or radar_status['shortTermUnavailable'] or radar_status['vehDynamicsError']: - errors.append('fault') - else: - radar_status = self.rcp.vl['TeslaRadarSguInfo'] - if radar_status['RADC_HWFail'] or radar_status['RADC_SGUFail'] or radar_status['RADC_SensorDirty']: - errors.append('fault') - - ret.errors = errors - - # Radar tracks - for i in range(self.num_points): - msg_a = self.rcp.vl[f'RadarPoint{i}_A'] - msg_b = self.rcp.vl[f'RadarPoint{i}_B'] - - # Make sure msg A and B are together - if msg_a['Index'] != msg_b['Index2']: - continue - - # Check if it's a valid track - if not msg_a['Tracked']: - if i in self.pts: - del self.pts[i] - continue - - # New track! - if i not in self.pts: - self.pts[i] = car.RadarData.RadarPoint.new_message() - self.pts[i].trackId = self.track_id - self.track_id += 1 - - # Parse track data - self.pts[i].dRel = msg_a['LongDist'] - self.pts[i].yRel = msg_a['LatDist'] - self.pts[i].vRel = msg_a['LongSpeed'] - self.pts[i].aRel = msg_a['LongAccel'] - self.pts[i].yvRel = msg_b['LatSpeed'] - self.pts[i].measured = bool(msg_a['Meas']) - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret diff --git a/selfdrive/car/tesla/teslacan.py b/selfdrive/car/tesla/teslacan.py deleted file mode 100644 index 22e0ac6c4ef6fc..00000000000000 --- a/selfdrive/car/tesla/teslacan.py +++ /dev/null @@ -1,94 +0,0 @@ -import crcmod - -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.tesla.values import CANBUS, CarControllerParams - - -class TeslaCAN: - def __init__(self, packer, pt_packer): - self.packer = packer - self.pt_packer = pt_packer - self.crc = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) - - @staticmethod - def checksum(msg_id, dat): - # TODO: get message ID from name instead - ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) - ret += sum(dat) - return ret & 0xFF - - def create_steering_control(self, angle, enabled, counter): - values = { - "DAS_steeringAngleRequest": -angle, - "DAS_steeringHapticRequest": 0, - "DAS_steeringControlType": 1 if enabled else 0, - "DAS_steeringControlCounter": counter, - } - - data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values)[1] - values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) - return self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values) - - def create_action_request(self, msg_stw_actn_req, cancel, bus, counter): - # We copy this whole message when spamming cancel - values = {s: msg_stw_actn_req[s] for s in [ - "SpdCtrlLvr_Stat", - "VSL_Enbl_Rq", - "SpdCtrlLvrStat_Inv", - "DTR_Dist_Rq", - "TurnIndLvr_Stat", - "HiBmLvr_Stat", - "WprWashSw_Psd", - "WprWash_R_Sw_Posn_V2", - "StW_Lvr_Stat", - "StW_Cond_Flt", - "StW_Cond_Psd", - "HrnSw_Psd", - "StW_Sw00_Psd", - "StW_Sw01_Psd", - "StW_Sw02_Psd", - "StW_Sw03_Psd", - "StW_Sw04_Psd", - "StW_Sw05_Psd", - "StW_Sw06_Psd", - "StW_Sw07_Psd", - "StW_Sw08_Psd", - "StW_Sw09_Psd", - "StW_Sw10_Psd", - "StW_Sw11_Psd", - "StW_Sw12_Psd", - "StW_Sw13_Psd", - "StW_Sw14_Psd", - "StW_Sw15_Psd", - "WprSw6Posn", - "MC_STW_ACTN_RQ", - "CRC_STW_ACTN_RQ", - ]} - - if cancel: - values["SpdCtrlLvr_Stat"] = 1 - values["MC_STW_ACTN_RQ"] = counter - - data = self.packer.make_can_msg("STW_ACTN_RQ", bus, values)[1] - values["CRC_STW_ACTN_RQ"] = self.crc(data[:7]) - return self.packer.make_can_msg("STW_ACTN_RQ", bus, values) - - def create_longitudinal_commands(self, acc_state, speed, min_accel, max_accel, cnt): - messages = [] - values = { - "DAS_setSpeed": speed * CV.MS_TO_KPH, - "DAS_accState": acc_state, - "DAS_aebEvent": 0, - "DAS_jerkMin": CarControllerParams.JERK_LIMIT_MIN, - "DAS_jerkMax": CarControllerParams.JERK_LIMIT_MAX, - "DAS_accelMin": min_accel, - "DAS_accelMax": max_accel, - "DAS_controlCounter": cnt, - "DAS_controlChecksum": 0, - } - - for packer, bus in [(self.packer, CANBUS.chassis), (self.pt_packer, CANBUS.powertrain)]: - data = packer.make_can_msg("DAS_control", bus, values)[1] - values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) - messages.append(packer.make_can_msg("DAS_control", bus, values)) - return messages diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py deleted file mode 100644 index 0f9cd00f63edeb..00000000000000 --- a/selfdrive/car/tesla/values.py +++ /dev/null @@ -1,98 +0,0 @@ -from collections import namedtuple - -from cereal import car -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - -Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) - -class CAR(Platforms): - TESLA_AP1_MODELS = PlatformConfig( - [CarDocs("Tesla AP1 Model S", "All")], - CarSpecs(mass=2100., wheelbase=2.959, steerRatio=15.0), - dbc_dict('tesla_powertrain', 'tesla_radar_bosch_generated', chassis_dbc='tesla_can') - ) - TESLA_AP2_MODELS = PlatformConfig( - [CarDocs("Tesla AP2 Model S", "All")], - TESLA_AP1_MODELS.specs, - TESLA_AP1_MODELS.dbc_dict - ) - TESLA_MODELS_RAVEN = PlatformConfig( - [CarDocs("Tesla Model S Raven", "All")], - TESLA_AP1_MODELS.specs, - dbc_dict('tesla_powertrain', 'tesla_radar_continental_generated', chassis_dbc='tesla_can') - ) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.eps], - rx_offset=0x08, - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.SUPPLIER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.SUPPLIER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.eps], - rx_offset=0x08, - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.adas, Ecu.electricBrakeBooster, Ecu.fwdRadar], - rx_offset=0x10, - bus=0, - ), - ] -) - -class CANBUS: - # Lateral harness - chassis = 0 - radar = 1 - autopilot_chassis = 2 - - # Longitudinal harness - powertrain = 4 - private = 5 - autopilot_powertrain = 6 - -GEAR_MAP = { - "DI_GEAR_INVALID": car.CarState.GearShifter.unknown, - "DI_GEAR_P": car.CarState.GearShifter.park, - "DI_GEAR_R": car.CarState.GearShifter.reverse, - "DI_GEAR_N": car.CarState.GearShifter.neutral, - "DI_GEAR_D": car.CarState.GearShifter.drive, - "DI_GEAR_SNA": car.CarState.GearShifter.unknown, -} - -DOORS = ["DOOR_STATE_FL", "DOOR_STATE_FR", "DOOR_STATE_RL", "DOOR_STATE_RR", "DOOR_STATE_FrontTrunk", "BOOT_STATE"] - -# Make sure the message and addr is also in the CAN parser! -BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.leftBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [1]), - Button(car.CarState.ButtonEvent.Type.rightBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [2]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [4, 16]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [8, 32]), - Button(car.CarState.ButtonEvent.Type.cancel, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [2]), -] - -class CarControllerParams: - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 1.6, .3]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 7.0, 0.8]) - JERK_LIMIT_MAX = 8 - JERK_LIMIT_MIN = -8 - ACCEL_TO_SPEED_MULTIPLIER = 3 - - def __init__(self, CP): - pass - - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/tests/big_cars_test.sh b/selfdrive/car/tests/big_cars_test.sh index af45c9cd1488ad..8b0e96d980670b 100755 --- a/selfdrive/car/tests/big_cars_test.sh +++ b/selfdrive/car/tests/big_cars_test.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash SCRIPT_DIR=$(dirname "$0") BASEDIR=$(realpath "$SCRIPT_DIR/../../../") @@ -9,4 +9,4 @@ INTERNAL_SEG_CNT=300 FILEREADER_CACHE=1 INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt -cd selfdrive/car/tests && pytest test_models.py test_car_interfaces.py \ No newline at end of file +cd selfdrive/car/tests && pytest test_models.py test_car_interfaces.py diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 7116375378b565..c9f57a4c712b7f 100755 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -1,19 +1,18 @@ #!/usr/bin/env python3 from typing import NamedTuple -from openpilot.selfdrive.car.chrysler.values import CAR as CHRYSLER -from openpilot.selfdrive.car.gm.values import CAR as GM -from openpilot.selfdrive.car.ford.values import CAR as FORD -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.hyundai.values import CAR as HYUNDAI -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.car.subaru.values import CAR as SUBARU -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.values import Platform -from openpilot.selfdrive.car.volkswagen.values import CAR as VOLKSWAGEN -from openpilot.selfdrive.car.tesla.values import CAR as TESLA -from openpilot.selfdrive.car.body.values import CAR as COMMA +from opendbc.car.chrysler.values import CAR as CHRYSLER +from opendbc.car.gm.values import CAR as GM +from opendbc.car.ford.values import CAR as FORD +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.hyundai.values import CAR as HYUNDAI +from opendbc.car.nissan.values import CAR as NISSAN +from opendbc.car.mazda.values import CAR as MAZDA +from opendbc.car.subaru.values import CAR as SUBARU +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.values import Platform +from opendbc.car.volkswagen.values import CAR as VOLKSWAGEN +from opendbc.car.body.values import CAR as COMMA # TODO: add routes for these cars non_tested_cars = [ @@ -290,10 +289,6 @@ class CarTestRoute(NamedTuple): CarTestRoute("f6d5b1a9d7a1c92e|2021-07-08--06-56-59", MAZDA.MAZDA_CX9_2021), CarTestRoute("a4af1602d8e668ac|2022-02-03--12-17-07", MAZDA.MAZDA_CX5_2022), - CarTestRoute("6c14ee12b74823ce|2021-06-30--11-49-02", TESLA.TESLA_AP1_MODELS), - CarTestRoute("bb50caf5f0945ab1|2021-06-19--17-20-18", TESLA.TESLA_AP2_MODELS), - CarTestRoute("66c1699b7697267d/2024-03-03--13-09-53", TESLA.TESLA_MODELS_RAVEN), - # Segments that test specific issues # Controls mismatch due to standstill threshold CarTestRoute("bec2dcfde6a64235|2022-04-08--14-21-32", HONDA.HONDA_CRV_HYBRID, segment=22), diff --git a/selfdrive/car/tests/test_can_fingerprint.py b/selfdrive/car/tests/test_can_fingerprint.py deleted file mode 100644 index e28b2fe3b40a60..00000000000000 --- a/selfdrive/car/tests/test_can_fingerprint.py +++ /dev/null @@ -1,56 +0,0 @@ -from parameterized import parameterized - -from openpilot.selfdrive.car.can_definitions import CanData -from openpilot.selfdrive.car.car_helpers import FRAME_FINGERPRINT, can_fingerprint -from openpilot.selfdrive.car.fingerprints import _FINGERPRINTS as FINGERPRINTS - - -class TestCanFingerprint: - @parameterized.expand(list(FINGERPRINTS.items())) - def test_can_fingerprint(self, car_model, fingerprints): - """Tests online fingerprinting function on offline fingerprints""" - - for fingerprint in fingerprints: # can have multiple fingerprints for each platform - can = [CanData(address=address, dat=b'\x00' * length, src=src) - for address, length in fingerprint.items() for src in (0, 1)] - - fingerprint_iter = iter([can]) - car_fingerprint, finger = can_fingerprint(lambda **kwargs: [next(fingerprint_iter, [])]) # noqa: B023 - - assert car_fingerprint == car_model - assert finger[0] == fingerprint - assert finger[1] == fingerprint - assert finger[2] == {} - - def test_timing(self, subtests): - # just pick any CAN fingerprinting car - car_model = "CHEVROLET_BOLT_EUV" - fingerprint = FINGERPRINTS[car_model][0] - - cases = [] - - # case 1 - one match, make sure we keep going for 100 frames - can = [CanData(address=address, dat=b'\x00' * length, src=src) - for address, length in fingerprint.items() for src in (0, 1)] - cases.append((FRAME_FINGERPRINT, car_model, can)) - - # case 2 - no matches, make sure we keep going for 100 frames - can = [CanData(address=1, dat=b'\x00' * 1, src=src) for src in (0, 1)] # uncommon address - cases.append((FRAME_FINGERPRINT, None, can)) - - # case 3 - multiple matches, make sure we keep going for 200 frames to try to eliminate some - can = [CanData(address=2016, dat=b'\x00' * 8, src=src) for src in (0, 1)] # common address - cases.append((FRAME_FINGERPRINT * 2, None, can)) - - for expected_frames, car_model, can in cases: - with subtests.test(expected_frames=expected_frames, car_model=car_model): - frames = 0 - - def can_recv(**kwargs): - nonlocal frames - frames += 1 - return [can] # noqa: B023 - - car_fingerprint, _ = can_fingerprint(can_recv) - assert car_fingerprint == car_model - assert frames == expected_frames + 2 # TODO: fix extra frames diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 9e3c7d157ef223..5a321efb16e503 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -6,11 +6,14 @@ from parameterized import parameterized from cereal import car, messaging -from openpilot.selfdrive.car import DT_CTRL, gen_empty_fingerprint -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.fingerprints import all_known_cars -from openpilot.selfdrive.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS -from openpilot.selfdrive.car.interfaces import get_interface_attr +from opendbc.car import DT_CTRL, gen_empty_fingerprint +from opendbc.car.car_helpers import interfaces +from opendbc.car.structs import CarParams +from opendbc.car.fingerprints import all_known_cars +from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS +from opendbc.car.interfaces import get_interface_attr +from opendbc.car.mock.values import CAR as MOCK +from openpilot.selfdrive.car.card import convert_carControl, convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque @@ -42,8 +45,8 @@ def get_fuzzy_car_interface_args(draw: DrawType) -> dict: }) params: dict = draw(params_strategy) - params['car_fw'] = [car.CarParams.CarFw(ecu=fw[0], address=fw[1], subAddress=fw[2] or 0, - request=draw(st.sampled_from(sorted(ALL_REQUESTS)))) + params['car_fw'] = [CarParams.CarFw(ecu=fw[0], address=fw[1], subAddress=fw[2] or 0, + request=draw(st.sampled_from(sorted(ALL_REQUESTS)))) for fw in params['car_fw']] return params @@ -51,7 +54,7 @@ def get_fuzzy_car_interface_args(draw: DrawType) -> dict: class TestCarInterfaces: # FIXME: Due to the lists used in carParams, Phase.target is very slow and will cause # many generated examples to overrun when max_examples > ~20, don't use it - @parameterized.expand([(car,) for car in sorted(all_known_cars())]) + @parameterized.expand([(car,) for car in sorted(all_known_cars())] + [MOCK.MOCK]) @settings(max_examples=MAX_EXAMPLES, deadline=None, phases=(Phase.reuse, Phase.generate, Phase.shrink)) @given(data=st.data()) @@ -62,7 +65,6 @@ def test_car_interfaces(self, car_name, data): car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], experimental_long=args['experimental_long'], docs=False) - car_params = car_params.as_reader() car_interface = CarInterface(car_params, CarController, CarState) assert car_params assert car_interface @@ -78,12 +80,13 @@ def test_car_interfaces(self, car_name, data): assert len(car_params.longitudinalTuning.kiV) == len(car_params.longitudinalTuning.kiBP) # Lateral sanity checks - if car_params.steerControlType != car.CarParams.SteerControlType.angle: + if car_params.steerControlType != CarParams.SteerControlType.angle: tune = car_params.lateralTuning if tune.which() == 'pid': - assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0 - assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP) - assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) + if car_name != MOCK.MOCK: + assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0 + assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP) + assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) elif tune.which() == 'torque': assert not math.isnan(tune.torque.kf) and tune.torque.kf > 0 @@ -93,31 +96,34 @@ def test_car_interfaces(self, car_name, data): # Run car interface now_nanos = 0 CC = car.CarControl.new_message(**cc_msg) + CC = convert_carControl(CC.as_reader()) for _ in range(10): - car_interface.update(CC, []) - car_interface.apply(CC.as_reader(), now_nanos) + car_interface.update([]) + car_interface.apply(CC, now_nanos) now_nanos += DT_CTRL * 1e9 # 10 ms CC = car.CarControl.new_message(**cc_msg) CC.enabled = True + CC = convert_carControl(CC.as_reader()) for _ in range(10): - car_interface.update(CC, []) - car_interface.apply(CC.as_reader(), now_nanos) + car_interface.update([]) + car_interface.apply(CC, now_nanos) now_nanos += DT_CTRL * 1e9 # 10ms # Test controller initialization # TODO: wait until card refactor is merged to run controller a few times, # hypothesis also slows down significantly with just one more message draw - LongControl(car_params) - if car_params.steerControlType == car.CarParams.SteerControlType.angle: - LatControlAngle(car_params, car_interface) + car_params_capnp = convert_to_capnp(car_params).as_reader() + LongControl(car_params_capnp) + if car_params.steerControlType == CarParams.SteerControlType.angle: + LatControlAngle(car_params_capnp, car_interface) elif car_params.lateralTuning.which() == 'pid': - LatControlPID(car_params, car_interface) + LatControlPID(car_params_capnp, car_interface) elif car_params.lateralTuning.which() == 'torque': - LatControlTorque(car_params, car_interface) + LatControlTorque(car_params_capnp, car_interface) # Test radar interface - RadarInterface = importlib.import_module(f'selfdrive.car.{car_params.carName}.radar_interface').RadarInterface + RadarInterface = importlib.import_module(f'opendbc.car.{car_params.carName}.radar_interface').RadarInterface radar_interface = RadarInterface(car_params) assert radar_interface @@ -136,7 +142,7 @@ def test_car_interfaces(self, car_name, data): def test_interface_attrs(self): """Asserts basic behavior of interface attribute getter""" num_brands = len(get_interface_attr('CAR')) - assert num_brands >= 13 + assert num_brands >= 12 # Should return value for all brands when not combining, even if attribute doesn't exist ret = get_interface_attr('FAKE_ATTR') diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index 40ad07b2837644..a203b2feff6d45 100644 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -1,16 +1,10 @@ -from collections import defaultdict import os -import pytest -import re from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE, generate_cars_md, get_all_car_docs -from openpilot.selfdrive.car.docs_definitions import Cable, Column, PartType, Star -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.values import PLATFORMS +from opendbc.car.docs import generate_cars_md, get_all_car_docs from openpilot.selfdrive.debug.dump_car_docs import dump_car_docs from openpilot.selfdrive.debug.print_docs_diff import print_car_docs_diff +from openpilot.selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE class TestCarDocs: @@ -23,69 +17,10 @@ def test_generator(self): with open(CARS_MD_OUT) as f: current_cars_md = f.read() - assert generated_cars_md == current_cars_md, "Run selfdrive/car/docs.py to update the compatibility documentation" + assert generated_cars_md == current_cars_md, "Run selfdrive/opcar/docs.py to update the compatibility documentation" def test_docs_diff(self): dump_path = os.path.join(BASEDIR, "selfdrive", "car", "tests", "cars_dump") dump_car_docs(dump_path) print_car_docs_diff(dump_path) os.remove(dump_path) - - def test_duplicate_years(self, subtests): - make_model_years = defaultdict(list) - for car in self.all_cars: - with subtests.test(car_docs_name=car.name): - make_model = (car.make, car.model) - for year in car.year_list: - assert year not in make_model_years[make_model], f"{car.name}: Duplicate model year" - make_model_years[make_model].append(year) - - def test_missing_car_docs(self, subtests): - all_car_docs_platforms = [name for name, config in PLATFORMS.items()] - for platform in sorted(interfaces.keys()): - with subtests.test(platform=platform): - assert platform in all_car_docs_platforms, f"Platform: {platform} doesn't have a CarDocs entry" - - def test_naming_conventions(self, subtests): - # Asserts market-standard car naming conventions by brand - for car in self.all_cars: - with subtests.test(car=car.name): - tokens = car.model.lower().split(" ") - if car.car_name == "hyundai": - assert "phev" not in tokens, "Use `Plug-in Hybrid`" - assert "hev" not in tokens, "Use `Hybrid`" - if "plug-in hybrid" in car.model.lower(): - assert "Plug-in Hybrid" in car.model, "Use correct capitalization" - if car.make != "Kia": - assert "ev" not in tokens, "Use `Electric`" - elif car.car_name == "toyota": - if "rav4" in tokens: - assert "RAV4" in car.model, "Use correct capitalization" - - def test_torque_star(self, subtests): - # Asserts brand-specific assumptions around steering torque star - for car in self.all_cars: - with subtests.test(car=car.name): - # honda sanity check, it's the definition of a no torque star - if car.car_fingerprint in (HONDA.HONDA_ACCORD, HONDA.HONDA_CIVIC, HONDA.HONDA_CRV, HONDA.HONDA_ODYSSEY, HONDA.HONDA_PILOT): - assert car.row[Column.STEERING_TORQUE] == Star.EMPTY, f"{car.name} has full torque star" - elif car.car_name in ("toyota", "hyundai"): - assert car.row[Column.STEERING_TORQUE] != Star.EMPTY, f"{car.name} has no torque star" - - def test_year_format(self, subtests): - for car in self.all_cars: - with subtests.test(car=car.name): - assert re.search(r"\d{4}-\d{4}", car.name) is None, f"Format years correctly: {car.name}" - - def test_harnesses(self, subtests): - for car in self.all_cars: - with subtests.test(car=car.name): - if car.name == "comma body": - pytest.skip() - - car_part_type = [p.part_type for p in car.car_parts.all_parts()] - car_parts = list(car.car_parts.all_parts()) - assert len(car_parts) > 0, f"Need to specify car parts: {car.name}" - assert car_part_type.count(PartType.connector) == 1, f"Need to specify one harness connector: {car.name}" - assert car_part_type.count(PartType.mount) == 1, f"Need to specify one mount: {car.name}" - assert Cable.right_angle_obd_c_cable_1_5ft in car_parts, f"Need to specify a right angle OBD-C cable (1.5ft): {car.name}" diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py deleted file mode 100644 index 46a432f8a238f2..00000000000000 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ /dev/null @@ -1,327 +0,0 @@ -import pytest -import random -import time -from collections import defaultdict -from parameterized import parameterized - -from cereal import car -from openpilot.selfdrive.car.can_definitions import CanData -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.fw_versions import ESSENTIAL_ECUS, FW_QUERY_CONFIGS, FUZZY_EXCLUDE_ECUS, VERSIONS, build_fw_dict, \ - match_fw_to_car, get_brand_ecu_matches, get_fw_versions, get_fw_versions_ordered, get_present_ecus -from openpilot.selfdrive.car.vin import get_vin - -CarFw = car.CarParams.CarFw -Ecu = car.CarParams.Ecu - -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -class TestFwFingerprint: - def assertFingerprints(self, candidates, expected): - candidates = list(candidates) - assert len(candidates) == 1, f"got more than one candidate: {candidates}" - assert candidates[0] == expected - - @parameterized.expand([(b, c, e[c], n) for b, e in VERSIONS.items() for c in e for n in (True, False)]) - def test_exact_match(self, brand, car_model, ecus, test_non_essential): - config = FW_QUERY_CONFIGS[brand] - CP = car.CarParams.new_message() - for _ in range(100): - fw = [] - for ecu, fw_versions in ecus.items(): - # Assume non-essential ECUs apply to all cars, so we catch cases where Car A with - # missing ECUs won't match to Car B where only Car B has labeled non-essential ECUs - if ecu[0] in config.non_essential_ecus and test_non_essential: - continue - - ecu_name, addr, sub_addr = ecu - fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, - "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) - CP.carFw = fw - _, matches = match_fw_to_car(CP.carFw, CP.carVin, allow_fuzzy=False) - if not test_non_essential: - self.assertFingerprints(matches, car_model) - else: - # if we're removing ECUs we expect some match loss, but it shouldn't mismatch - if len(matches) != 0: - self.assertFingerprints(matches, car_model) - - @parameterized.expand([(b, c, e[c]) for b, e in VERSIONS.items() for c in e]) - def test_custom_fuzzy_match(self, brand, car_model, ecus): - # Assert brand-specific fuzzy fingerprinting function doesn't disagree with standard fuzzy function - config = FW_QUERY_CONFIGS[brand] - if config.match_fw_to_car_fuzzy is None: - pytest.skip("Brand does not implement custom fuzzy fingerprinting function") - - CP = car.CarParams.new_message() - for _ in range(5): - fw = [] - for ecu, fw_versions in ecus.items(): - ecu_name, addr, sub_addr = ecu - fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, - "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) - CP.carFw = fw - _, matches = match_fw_to_car(CP.carFw, CP.carVin, allow_exact=False, log=False) - brand_matches = config.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, VERSIONS[brand]) - - # If both have matches, they must agree - if len(matches) == 1 and len(brand_matches) == 1: - assert matches == brand_matches - - @parameterized.expand([(b, c, e[c]) for b, e in VERSIONS.items() for c in e]) - def test_fuzzy_match_ecu_count(self, brand, car_model, ecus): - # Asserts that fuzzy matching does not count matching FW, but ECU address keys - valid_ecus = [e for e in ecus if e[0] not in FUZZY_EXCLUDE_ECUS] - if not len(valid_ecus): - pytest.skip("Car model has no compatible ECUs for fuzzy matching") - - fw = [] - for ecu in valid_ecus: - ecu_name, addr, sub_addr = ecu - for _ in range(5): - # Add multiple FW versions to simulate ECU returning to multiple queries in a brand - fw.append({"ecu": ecu_name, "fwVersion": random.choice(ecus[ecu]), 'brand': brand, - "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) - CP = car.CarParams.new_message(carFw=fw) - _, matches = match_fw_to_car(CP.carFw, CP.carVin, allow_exact=False, log=False) - - # Assert no match if there are not enough unique ECUs - unique_ecus = {(f['address'], f['subAddress']) for f in fw} - if len(unique_ecus) < 2: - assert len(matches) == 0, car_model - # There won't always be a match due to shared FW, but if there is it should be correct - elif len(matches): - self.assertFingerprints(matches, car_model) - - def test_fw_version_lists(self, subtests): - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, ecu_fw in ecus.items(): - with subtests.test(ecu): - duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} - assert not len(duplicates), f'{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}' - assert len(ecu_fw) > 0, f'{car_model}: No FW versions: Ecu.{ECU_NAME[ecu[0]]}' - - def test_all_addrs_map_to_one_ecu(self): - for brand, cars in VERSIONS.items(): - addr_to_ecu = defaultdict(set) - for ecus in cars.values(): - for ecu_type, addr, sub_addr in ecus.keys(): - addr_to_ecu[(addr, sub_addr)].add(ecu_type) - ecus_for_addr = addr_to_ecu[(addr, sub_addr)] - ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_for_addr]) - assert len(ecus_for_addr) <= 1, f"{brand} has multiple ECUs that map to one address: {ecu_strings} -> ({hex(addr)}, {sub_addr})" - - def test_data_collection_ecus(self, subtests): - # Asserts no extra ECUs are in the fingerprinting database - for brand, config in FW_QUERY_CONFIGS.items(): - for car_model, ecus in VERSIONS[brand].items(): - bad_ecus = set(ecus).intersection(config.extra_ecus) - with subtests.test(car_model=car_model.value): - assert not len(bad_ecus), f'{car_model}: Fingerprints contain ECUs added for data collection: {bad_ecus}' - - def test_blacklisted_ecus(self, subtests): - blacklisted_addrs = (0x7c4, 0x7d0) # includes A/C ecu and an unknown ecu - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - CP = interfaces[car_model][0].get_non_essential_params(car_model) - if CP.carName == 'subaru': - for ecu in ecus.keys(): - assert ecu[1] not in blacklisted_addrs, f'{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})' - - elif CP.carName == "chrysler": - # Some HD trucks have a combined TCM and ECM - if CP.carFingerprint.startswith("RAM HD"): - for ecu in ecus.keys(): - assert ecu[0] != Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})" - - def test_non_essential_ecus(self, subtests): - for brand, config in FW_QUERY_CONFIGS.items(): - with subtests.test(brand): - # These ECUs are already not in ESSENTIAL_ECUS which the fingerprint functions give a pass if missing - unnecessary_non_essential_ecus = set(config.non_essential_ecus) - set(ESSENTIAL_ECUS) - assert unnecessary_non_essential_ecus == set(), "Declaring non-essential ECUs non-essential is not required: " + \ - f"{', '.join([f'Ecu.{ECU_NAME[ecu]}' for ecu in unnecessary_non_essential_ecus])}" - - def test_missing_versions_and_configs(self, subtests): - brand_versions = set(VERSIONS.keys()) - brand_configs = set(FW_QUERY_CONFIGS.keys()) - if len(brand_configs - brand_versions): - with subtests.test(): - pytest.fail(f"Brands do not implement FW_VERSIONS: {brand_configs - brand_versions}") - - if len(brand_versions - brand_configs): - with subtests.test(): - pytest.fail(f"Brands do not implement FW_QUERY_CONFIG: {brand_versions - brand_configs}") - - # Ensure each brand has at least 1 ECU to query, and extra ECU retrieval - for brand, config in FW_QUERY_CONFIGS.items(): - assert len(config.get_all_ecus({}, include_extra_ecus=False)) == 0 - assert config.get_all_ecus({}) == set(config.extra_ecus) - assert len(config.get_all_ecus(VERSIONS[brand])) > 0 - - def test_fw_request_ecu_whitelist(self, subtests): - for brand, config in FW_QUERY_CONFIGS.items(): - with subtests.test(brand=brand): - whitelisted_ecus = {ecu for r in config.requests for ecu in r.whitelist_ecus} - brand_ecus = {fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw} - brand_ecus |= {ecu[0] for ecu in config.extra_ecus} - - # each ecu in brand's fw versions + extra ecus needs to be whitelisted at least once - ecus_not_whitelisted = brand_ecus - whitelisted_ecus - - ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) - assert not (len(whitelisted_ecus) and len(ecus_not_whitelisted)), \ - f'{brand.title()}: ECUs not in any FW query whitelists: {ecu_strings}' - - def test_fw_requests(self, subtests): - # Asserts equal length request and response lists - for brand, config in FW_QUERY_CONFIGS.items(): - with subtests.test(brand=brand): - for request_obj in config.requests: - assert len(request_obj.request) == len(request_obj.response) - - # No request on the OBD port (bus 1, multiplexed) should be run on an aux panda - assert not (request_obj.auxiliary and request_obj.bus == 1 and request_obj.obd_multiplexing), \ - f"{brand.title()}: OBD multiplexed request is marked auxiliary: {request_obj}" - - def test_brand_ecu_matches(self): - empty_response = {brand: set() for brand in FW_QUERY_CONFIGS} - assert get_brand_ecu_matches(set()) == empty_response - - # we ignore bus - expected_response = empty_response | {'toyota': {(0x750, 0xf)}} - assert get_brand_ecu_matches({(0x758, 0xf, 99)}) == expected_response - - -class TestFwFingerprintTiming: - N: int = 5 - TOL: float = 0.05 - - # for patched functions - current_obd_multiplexing: bool - total_time: float - - @staticmethod - def fake_can_send(msgs): - pass - - @staticmethod - def fake_can_recv(wait_for_one: bool = False) -> list[list[CanData]]: - return ([[CanData(random.randint(0x600, 0x800), b'\x00' * 8, 0)]] - if random.uniform(0, 1) > 0.5 else []) - - def fake_set_obd_multiplexing(self, obd_multiplexing): - """The 10Hz blocking params loop adds on average 50ms to the query time for each OBD multiplexing change""" - if obd_multiplexing != self.current_obd_multiplexing: - self.current_obd_multiplexing = obd_multiplexing - self.total_time += 0.1 / 2 - - def fake_get_data(self, timeout): - self.total_time += timeout - return {} - - def _benchmark_brand(self, brand, num_pandas, mocker): - self.total_time = 0 - mocker.patch("openpilot.selfdrive.car.isotp_parallel_query.IsoTpParallelQuery.get_data", self.fake_get_data) - for _ in range(self.N): - # Treat each brand as the most likely (aka, the first) brand with OBD multiplexing initially on - self.current_obd_multiplexing = True - - t = time.perf_counter() - get_fw_versions(self.fake_can_recv, self.fake_can_send, self.fake_set_obd_multiplexing, brand, num_pandas=num_pandas) - self.total_time += time.perf_counter() - t - - return self.total_time / self.N - - def _assert_timing(self, avg_time, ref_time): - assert avg_time < ref_time + self.TOL - assert avg_time > ref_time - self.TOL, "Performance seems to have improved, update test refs." - - def test_startup_timing(self, subtests, mocker): - # Tests worse-case VIN query time and typical present ECU query time - vin_ref_times = {'worst': 1.4, 'best': 0.7} # best assumes we go through all queries to get a match - present_ecu_ref_time = 0.45 - - def fake_get_ecu_addrs(*_, timeout): - self.total_time += timeout - return set() - - self.total_time = 0.0 - mocker.patch("openpilot.selfdrive.car.fw_versions.get_ecu_addrs", fake_get_ecu_addrs) - for _ in range(self.N): - self.current_obd_multiplexing = True - get_present_ecus(self.fake_can_recv, self.fake_can_send, self.fake_set_obd_multiplexing, num_pandas=2) - self._assert_timing(self.total_time / self.N, present_ecu_ref_time) - print(f'get_present_ecus, query time={self.total_time / self.N} seconds') - - for name, args in (('worst', {}), ('best', {'retry': 1})): - with subtests.test(name=name): - self.total_time = 0.0 - mocker.patch("openpilot.selfdrive.car.isotp_parallel_query.IsoTpParallelQuery.get_data", self.fake_get_data) - for _ in range(self.N): - get_vin(self.fake_can_recv, self.fake_can_send, (0, 1), **args) - self._assert_timing(self.total_time / self.N, vin_ref_times[name]) - print(f'get_vin {name} case, query time={self.total_time / self.N} seconds') - - def test_fw_query_timing(self, subtests, mocker): - total_ref_time = {1: 7.2, 2: 7.8} - brand_ref_times = { - 1: { - 'gm': 1.0, - 'body': 0.1, - 'chrysler': 0.3, - 'ford': 1.5, - 'honda': 0.45, - 'hyundai': 0.65, - 'mazda': 0.1, - 'nissan': 0.8, - 'subaru': 0.65, - 'tesla': 0.3, - 'toyota': 0.7, - 'volkswagen': 0.65, - }, - 2: { - 'ford': 1.6, - 'hyundai': 1.15, - 'tesla': 0.3, - } - } - - total_times = {1: 0.0, 2: 0.0} - for num_pandas in (1, 2): - for brand, config in FW_QUERY_CONFIGS.items(): - with subtests.test(brand=brand, num_pandas=num_pandas): - avg_time = self._benchmark_brand(brand, num_pandas, mocker) - total_times[num_pandas] += avg_time - avg_time = round(avg_time, 2) - - ref_time = brand_ref_times[num_pandas].get(brand) - if ref_time is None: - # ref time should be same as 1 panda if no aux queries - ref_time = brand_ref_times[num_pandas - 1][brand] - - self._assert_timing(avg_time, ref_time) - print(f'{brand=}, {num_pandas=}, {len(config.requests)=}, avg FW query time={avg_time} seconds') - - for num_pandas in (1, 2): - with subtests.test(brand='all_brands', num_pandas=num_pandas): - total_time = round(total_times[num_pandas], 2) - self._assert_timing(total_time, total_ref_time[num_pandas]) - print(f'all brands, total FW query time={total_time} seconds') - - def test_get_fw_versions(self, subtests, mocker): - # some coverage on IsoTpParallelQuery and panda UDS library - # TODO: replace this with full fingerprint simulation testing - # https://github.com/commaai/panda/pull/1329 - - def fake_carlog_exception(*args, **kwargs): - raise - - mocker.patch("openpilot.selfdrive.car.carlog.exception", fake_carlog_exception) - get_fw_versions_ordered(self.fake_can_recv, self.fake_can_send, lambda obd: None, '0' * 17, set()) - for brand in FW_QUERY_CONFIGS.keys(): - with subtests.test(brand=brand): - get_fw_versions(self.fake_can_recv, self.fake_can_send, lambda obd: None, brand) diff --git a/selfdrive/car/tests/test_lateral_limits.py b/selfdrive/car/tests/test_lateral_limits.py index 24eac01fcd9739..87c7a5e25624aa 100755 --- a/selfdrive/car/tests/test_lateral_limits.py +++ b/selfdrive/car/tests/test_lateral_limits.py @@ -5,10 +5,10 @@ import pytest import sys -from openpilot.selfdrive.car import DT_CTRL -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.fingerprints import all_known_cars -from openpilot.selfdrive.car.interfaces import get_torque_params +from opendbc.car import DT_CTRL +from opendbc.car.car_helpers import interfaces +from opendbc.car.fingerprints import all_known_cars +from opendbc.car.interfaces import get_torque_params CAR_MODELS = all_known_cars() @@ -41,7 +41,7 @@ def setup_class(cls): if CP.notCar: pytest.skip() - CarControllerParams = importlib.import_module(f'selfdrive.car.{CP.carName}.values').CarControllerParams + CarControllerParams = importlib.import_module(f'opendbc.car.{CP.carName}.values').CarControllerParams cls.control_params = CarControllerParams(CP) cls.torque_params = get_torque_params()[cls.car_model] diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index f57def03628bd2..dfb1712ab41163 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -1,4 +1,6 @@ import capnp +import copy +import dataclasses import os import importlib import pytest @@ -12,13 +14,13 @@ from cereal import messaging, log, car from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.car import DT_CTRL, gen_empty_fingerprint -from openpilot.selfdrive.car.fingerprints import all_known_cars, MIGRATION -from openpilot.selfdrive.car.car_helpers import FRAME_FINGERPRINT, interfaces -from openpilot.selfdrive.car.honda.values import CAR as HONDA, HondaFlags +from opendbc.car import DT_CTRL, gen_empty_fingerprint, structs +from opendbc.car.fingerprints import all_known_cars, MIGRATION +from opendbc.car.car_helpers import FRAME_FINGERPRINT, interfaces +from opendbc.car.honda.values import CAR as HONDA, HondaFlags +from opendbc.car.values import Platform from openpilot.selfdrive.car.tests.routes import non_tested_cars, routes, CarTestRoute -from openpilot.selfdrive.car.values import Platform -from openpilot.selfdrive.car.card import Car +from openpilot.selfdrive.car.card import Car, convert_to_capnp 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 @@ -181,7 +183,7 @@ def tearDownClass(cls): del cls.can_msgs def setUp(self): - self.CI = self.CarInterface(self.CP.copy(), self.CarController, self.CarState) + self.CI = self.CarInterface(copy.deepcopy(self.CP), self.CarController, self.CarState) assert self.CI Params().put_bool("OpenpilotEnabledToggle", self.openpilot_enabled) @@ -189,7 +191,7 @@ def setUp(self): # TODO: check safetyModel is in release panda build self.safety = libpanda_py.libpanda - cfg = self.CP.safetyConfigs[-1] + cfg = car.CarParams.SafetyConfig(**dataclasses.asdict(self.CP.safetyConfigs[-1])) set_status = self.safety.set_safety_hooks(cfg.safetyModel.raw, cfg.safetyParam) self.assertEqual(0, set_status, f"failed to set safetyModel {cfg}") self.safety.init_tests() @@ -201,7 +203,7 @@ def test_car_params(self): # make sure car params are within a valid range self.assertGreater(self.CP.mass, 1) - if self.CP.steerControlType != car.CarParams.SteerControlType.angle: + if self.CP.steerControlType != structs.CarParams.SteerControlType.angle: tuning = self.CP.lateralTuning.which() if tuning == 'pid': self.assertTrue(len(self.CP.lateralTuning.pid.kpV)) @@ -214,10 +216,10 @@ def test_car_interface(self): # TODO: also check for checksum violations from can parser can_invalid_cnt = 0 can_valid = False - CC = car.CarControl.new_message().as_reader() + CC = structs.CarControl() for i, msg in enumerate(self.can_msgs): - CS = self.CI.update(CC, can_capnp_to_list((msg.as_builder().to_bytes(),))) + CS = self.CI.update(can_capnp_to_list((msg.as_builder().to_bytes(),))) self.CI.apply(CC, msg.logMonoTime) if CS.canValid: @@ -230,7 +232,7 @@ def test_car_interface(self): self.assertEqual(can_invalid_cnt, 0) def test_radar_interface(self): - RadarInterface = importlib.import_module(f'selfdrive.car.{self.CP.carName}.radar_interface').RadarInterface + RadarInterface = importlib.import_module(f'opendbc.car.{self.CP.carName}.radar_interface').RadarInterface RI = RadarInterface(self.CP) assert RI @@ -238,9 +240,9 @@ def test_radar_interface(self): # start parsing CAN messages after we've left ELM mode and can expect CAN traffic error_cnt = 0 for i, msg in enumerate(self.can_msgs[self.elm_frame:]): - rr = RI.update(can_capnp_to_list((msg.as_builder().to_bytes(),))) + rr: structs.RadarData | None = RI.update(can_capnp_to_list((msg.as_builder().to_bytes(),))) if rr is not None and i > 50: - error_cnt += car.RadarData.Error.canError in rr.errors + error_cnt += structs.RadarData.Error.canError in rr.errors self.assertEqual(error_cnt, 0) def test_panda_safety_rx_checks(self): @@ -293,7 +295,7 @@ def test_car_controller(car_control): msgs_sent = 0 CI = self.CarInterface(self.CP, self.CarController, self.CarState) for _ in range(round(10.0 / DT_CTRL)): # make sure we hit the slowest messages - CI.update(car_control, []) + CI.update([]) _, sendcan = CI.apply(car_control, now_nanos) now_nanos += DT_CTRL * 1e9 @@ -306,18 +308,18 @@ def test_car_controller(car_control): self.assertGreater(msgs_sent, 50) # Make sure we can send all messages while inactive - CC = car.CarControl.new_message() - test_car_controller(CC.as_reader()) + CC = structs.CarControl() + test_car_controller(CC) # Test cancel + general messages (controls_allowed=False & cruise_engaged=True) self.safety.set_cruise_engaged_prev(True) - CC = car.CarControl.new_message(cruiseControl={'cancel': True}) - test_car_controller(CC.as_reader()) + CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(cancel=True)) + test_car_controller(CC) # Test resume + general messages (controls_allowed=True & cruise_engaged=True) self.safety.set_controls_allowed(True) - CC = car.CarControl.new_message(cruiseControl={'resume': True}) - test_car_controller(CC.as_reader()) + CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(resume=True)) + test_car_controller(CC) # Skip stdout/stderr capture with pytest, causes elevated memory usage @pytest.mark.nocapture @@ -339,8 +341,6 @@ def test_panda_safety_carstate_fuzzy(self, data): msg_strategy = st.binary(min_size=size, max_size=size) msgs = data.draw(st.lists(msg_strategy, min_size=20)) - CC = car.CarControl.new_message() - for dat in msgs: # due to panda updating state selectively, only edges are expected to match # TODO: warm up CarState with real CAN messages to check edge of both sources @@ -358,7 +358,7 @@ def test_panda_safety_carstate_fuzzy(self, data): can = messaging.new_message('can', 1) can.can = [log.CanData(address=address, dat=dat, src=bus)] - CS = self.CI.update(CC, can_capnp_to_list((can.to_bytes(),))) + CS = self.CI.update(can_capnp_to_list((can.to_bytes(),))) if self.safety.get_gas_pressed_prev() != prev_panda_gas: self.assertEqual(CS.gasPressed, self.safety.get_gas_pressed_prev()) @@ -393,11 +393,9 @@ def test_panda_safety_carstate(self): if self.CP.dashcamOnly: self.skipTest("no need to check panda safety for dashcamOnly") - CC = car.CarControl.new_message() - # warm up pass, as initial states may be different for can in self.can_msgs[:300]: - self.CI.update(CC, can_capnp_to_list((can.as_builder().to_bytes(), ))) + self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), ))) for msg in filter(lambda m: m.src in range(64), can.can): to_send = libpanda_py.make_CANPacket(msg.address, msg.src % 4, msg.dat) self.safety.safety_rx_hook(to_send) @@ -407,7 +405,7 @@ def test_panda_safety_carstate(self): checks = defaultdict(int) card = Car(CI=self.CI) for idx, can in enumerate(self.can_msgs): - CS = self.CI.update(CC, can_capnp_to_list((can.as_builder().to_bytes(), ))) + CS = convert_to_capnp(self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), )))) for msg in filter(lambda m: m.src in range(64), can.can): to_send = libpanda_py.make_CANPacket(msg.address, msg.src % 4, msg.dat) ret = self.safety.safety_rx_hook(to_send) diff --git a/selfdrive/car/tests/test_platform_configs.py b/selfdrive/car/tests/test_platform_configs.py deleted file mode 100644 index 31e4be4fe6b0e2..00000000000000 --- a/selfdrive/car/tests/test_platform_configs.py +++ /dev/null @@ -1,17 +0,0 @@ -from openpilot.selfdrive.car.values import PLATFORMS - - -class TestPlatformConfigs: - def test_configs(self, subtests): - - for name, platform in PLATFORMS.items(): - with subtests.test(platform=str(platform)): - assert platform.config._frozen - - if platform != "MOCK": - assert "pt" in platform.config.dbc_dict - assert len(platform.config.platform_str) > 0 - - assert name == platform.config.platform_str - - assert platform.config.specs is not None diff --git a/selfdrive/car/torque_data/neural_ff_weights.json b/selfdrive/car/torque_data/neural_ff_weights.json deleted file mode 100644 index 251b66efb0287d..00000000000000 --- a/selfdrive/car/torque_data/neural_ff_weights.json +++ /dev/null @@ -1 +0,0 @@ -{"CHEVROLET_BOLT_EUV": {"w_1": [[0.3452189564704895, -0.15614677965641022, -0.04062516987323761, -0.5960758328437805, 0.3211185932159424, 0.31732726097106934, -0.04430829733610153, -0.37327295541763306, -0.14118380844593048, 0.12712529301643372, 0.2641555070877075, -0.3451094627380371, -0.005127656273543835, 0.6185108423233032, 0.03725295141339302, 0.3763789236545563], [-0.0708412230014801, 0.3667356073856354, 0.031383827328681946, 0.1740853488445282, -0.04695861041545868, 0.018055908381938934, 0.009072160348296165, -0.23640218377113342, -0.10362917929887772, 0.022628149017691612, -0.224413201212883, 0.20718418061733246, -0.016947750002145767, -0.3872031271457672, -0.15500062704086304, -0.06375953555107117], [-0.0838046595454216, -0.0242826659232378, -0.07765661180019379, 0.028858814388513565, -0.09516210108995438, 0.008368706330657005, 0.1689300835132599, 0.015036891214549541, -0.15121428668498993, 0.1388195902109146, 0.11486363410949707, 0.0651545450091362, 0.13559958338737488, 0.04300367832183838, -0.13856294751167297, -0.058136988431215286], [-0.006249868310987949, 0.08809533715248108, -0.040690965950489044, 0.02359287068247795, -0.00766348373144865, 0.24816390872001648, -0.17360293865203857, -0.03676899895071983, -0.17564819753170013, 0.18998438119888306, -0.050583917647600174, -0.006488069426268339, 0.10649101436138153, -0.024557121098041534, -0.103276826441288, 0.18448011577129364]], "b_1": [0.2935388386249542, 0.10967712104320526, -0.014007942751049995, 0.211833655834198, 0.33605605363845825, 0.37722209095954895, -0.16615016758441925, 0.3134673535823822, 0.06695777177810669, 0.3425212800502777, 0.3769673705101013, 0.23186539113521576, 0.5770409107208252, -0.05929069593548775, 0.01839117519557476, 0.03828774020075798], "w_2": [[-0.06261160969734192, 0.010185074992477894, -0.06083013117313385, -0.04531499370932579, -0.08979734033346176, 0.3432150185108185, -0.019801849499344826, 0.3010321259498596], [0.19698476791381836, -0.009238275699317455, 0.08842222392559052, -0.09516377002000809, -0.05022778362035751, 0.13626104593276978, -0.052890390157699585, 0.15569131076335907], [0.0724768117070198, -0.09018408507108688, 0.06850195676088333, -0.025572121143341064, 0.0680626779794693, -0.07648195326328278, 0.07993496209383011, -0.059752143919467926], [1.267876386642456, -0.05755887180566788, -0.08429178595542908, 0.021366603672504425, -0.0006479775765910745, -1.4292563199996948, -0.08077696710824966, -1.414825439453125], [0.04535430669784546, 0.06555880606174469, -0.027145234867930412, -0.07661093026399612, -0.05702832341194153, 0.23650476336479187, 0.0024587824009358883, 0.20126521587371826], [0.006042032968252897, 0.042880818247795105, 0.002187949838116765, -0.017126334831118584, -0.08352015167474747, 0.19801731407642365, -0.029196614399552345, 0.23713473975658417], [-0.01644900068640709, -0.04358499124646187, 0.014584392309188843, 0.07155826687812805, -0.09354910999536514, -0.033351872116327286, 0.07138452678918839, -0.04755295440554619], [-1.1012420654296875, -0.03534531593322754, 0.02167935110628605, -0.01116552110761404, -0.08436500281095505, 1.1038788557052612, 0.027903547510504723, 1.0676132440567017], [0.03843916580080986, -0.0952216386795044, 0.039226632565259933, 0.002778085647150874, -0.020275786519050598, -0.07848760485649109, 0.04803166165947914, 0.015538203530013561], [0.018385495990514755, -0.025189843028783798, 0.0036680365446954966, -0.02105865254998207, 0.04808586835861206, 0.1575016975402832, 0.02703506126999855, 0.23039312660694122], [-0.0033881019335240126, -0.10210853815078735, -0.04877309128642082, 0.006989633198827505, 0.046798162162303925, 0.38676899671554565, -0.032304272055625916, 0.2345031052827835], [0.22092825174331665, -0.09642873704433441, 0.04499409720301628, 0.05108088254928589, -0.10191166400909424, 0.12818090617656708, -0.021021494641900063, 0.09440375864505768], [0.1212429478764534, -0.028194155544042587, -0.0981956496834755, 0.08226924389600754, 0.055346839129924774, 0.27067816257476807, -0.09064067900180817, 0.12580905854701996], [-1.6740131378173828, -0.02066155895590782, -0.05924689769744873, 0.06347910314798355, -0.07821853458881378, 1.2807466983795166, 0.04589352011680603, 1.310766577720642], [-0.09893272817134857, -0.04093599319458008, -0.02502273954451084, 0.09490344673395157, -0.0211324505507946, -0.09021010994911194, 0.07936318963766098, -0.03593116253614426], [-0.08490308374166489, -0.015558987855911255, -0.048692114651203156, -0.007421435788273811, -0.040531404316425323, 0.25889304280281067, 0.06012800335884094, 0.27946868538856506]], "b_2": [0.07973937690258026, -0.010446485131978989, -0.003066520905122161, -0.031895797699689865, 0.006032303906977177, 0.24106740951538086, -0.008969511836767197, 0.2872662842273712], "w_3": [[-1.364486813545227, -0.11682678014039993, 0.01764785870909691, 0.03926877677440643], [-0.05695437639951706, 0.05472218990325928, 0.1266128271818161, 0.09950875490903854], [0.11415273696184158, -0.10069356113672256, 0.0864749327301979, -0.043946366757154465], [-0.10138195008039474, -0.040128443390131, -0.08937158435583115, -0.0048376512713730335], [-0.0028251828625798225, -0.04743027314543724, 0.06340016424655914, 0.07277824729681015], [0.49482327699661255, -0.06410001963376999, -0.0999293103814125, -0.14250673353672028], [0.042802367359399796, 0.0015462725423276424, -0.05991362780332565, 0.1022040992975235], [0.3523194193840027, 0.07343732565641403, 0.04157765582203865, -0.12358107417821884]], "b_3": [0.2653026282787323, -0.058485131710767746, -0.0744510293006897, 0.012550175189971924], "w_4": [[0.5988775491714478, 0.09668736904859543], [-0.04360569268465042, 0.06491032242774963], [-0.11868984252214432, -0.09601487964391708], [-0.06554870307445526, -0.14189276099205017]], "b_4": [-0.08148707449436188, -2.8251802921295166], "input_norm_mat": [[-3.0, 3.0], [-3.0, 3.0], [0.0, 40.0], [-3.0, 3.0]], "output_norm_mat": [-1.0, 1.0], "temperature": 100.0}} \ No newline at end of file diff --git a/selfdrive/car/torque_data/override.toml b/selfdrive/car/torque_data/override.toml deleted file mode 100644 index 993eb3fb3c0fa5..00000000000000 --- a/selfdrive/car/torque_data/override.toml +++ /dev/null @@ -1,77 +0,0 @@ -legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] -### angle control -# Nissan appears to have torque -"NISSAN_XTRAIL" = [nan, 1.5, nan] -"NISSAN_ALTIMA" = [nan, 1.5, nan] -"NISSAN_LEAF_IC" = [nan, 1.5, nan] -"NISSAN_LEAF" = [nan, 1.5, nan] -"NISSAN_ROGUE" = [nan, 1.5, nan] - -# New subarus angle based controllers -"SUBARU_FORESTER_2022" = [nan, 3.0, nan] -"SUBARU_OUTBACK_2023" = [nan, 3.0, nan] -"SUBARU_ASCENT_2023" = [nan, 3.0, nan] - -# Toyota LTA also has torque -"TOYOTA_RAV4_TSS2_2023" = [nan, 3.0, nan] - -# Tesla has high torque -"TESLA_AP1_MODELS" = [nan, 2.5, nan] -"TESLA_AP2_MODELS" = [nan, 2.5, nan] -"TESLA_MODELS_RAVEN" = [nan, 2.5, nan] - -# Guess -"FORD_BRONCO_SPORT_MK1" = [nan, 1.5, nan] -"FORD_ESCAPE_MK4" = [nan, 1.5, nan] -"FORD_EXPLORER_MK6" = [nan, 1.5, nan] -"FORD_F_150_MK14" = [nan, 1.5, nan] -"FORD_FOCUS_MK4" = [nan, 1.5, nan] -"FORD_MAVERICK_MK1" = [nan, 1.5, nan] -"FORD_F_150_LIGHTNING_MK1" = [nan, 1.5, nan] -"FORD_MUSTANG_MACH_E_MK1" = [nan, 1.5, nan] -"FORD_RANGER_MK2" = [nan, 1.5, nan] -### - -# No steering wheel -"COMMA_BODY" = [nan, 1000, nan] - -# Totally new cars -"RAM_1500_5TH_GEN" = [2.0, 2.0, 0.05] -"RAM_HD_5TH_GEN" = [1.4, 1.4, 0.05] -"SUBARU_OUTBACK" = [2.0, 1.5, 0.2] -"CADILLAC_ESCALADE" = [1.899999976158142, 1.842270016670227, 0.1120000034570694] -"CADILLAC_ESCALADE_ESV_2019" = [1.15, 1.3, 0.2] -"CHEVROLET_BOLT_EUV" = [2.0, 2.0, 0.05] -"CHEVROLET_SILVERADO" = [1.9, 1.9, 0.112] -"CHEVROLET_TRAILBLAZER" = [1.33, 1.9, 0.16] -"CHEVROLET_EQUINOX" = [2.5, 2.5, 0.05] -"VOLKSWAGEN_CADDY_MK3" = [1.2, 1.2, 0.1] -"VOLKSWAGEN_PASSAT_NMS" = [2.5, 2.5, 0.1] -"VOLKSWAGEN_SHARAN_MK2" = [2.5, 2.5, 0.1] -"HYUNDAI_SANTA_CRUZ_1ST_GEN" = [2.7, 2.7, 0.1] -"KIA_SPORTAGE_5TH_GEN" = [2.6, 2.6, 0.1] -"GENESIS_GV70_1ST_GEN" = [2.42, 2.42, 0.1] -"GENESIS_GV60_EV_1ST_GEN" = [2.5, 2.5, 0.1] -"KIA_SORENTO_4TH_GEN" = [2.5, 2.5, 0.1] -"KIA_SORENTO_HEV_4TH_GEN" = [2.5, 2.5, 0.1] -"KIA_NIRO_HEV_2ND_GEN" = [2.42, 2.5, 0.12] -"KIA_NIRO_EV_2ND_GEN" = [2.05, 2.5, 0.14] -"GENESIS_GV80" = [2.5, 2.5, 0.1] -"KIA_CARNIVAL_4TH_GEN" = [1.75, 1.75, 0.15] -"GMC_ACADIA" = [1.6, 1.6, 0.2] -"LEXUS_IS_TSS2" = [2.0, 2.0, 0.1] -"HYUNDAI_KONA_EV_2ND_GEN" = [2.5, 2.5, 0.1] -"HYUNDAI_IONIQ_6" = [2.5, 2.5, 0.005] -"HYUNDAI_AZERA_6TH_GEN" = [1.8, 1.8, 0.1] -"HYUNDAI_AZERA_HEV_6TH_GEN" = [1.8, 1.8, 0.1] -"KIA_K8_HEV_1ST_GEN" = [2.5, 2.5, 0.1] -"HYUNDAI_CUSTIN_1ST_GEN" = [2.5, 2.5, 0.1] -"LEXUS_GS_F" = [2.5, 2.5, 0.08] -"HYUNDAI_STARIA_4TH_GEN" = [1.8, 2.0, 0.15] - -# Dashcam or fallback configured as ideal car -"MOCK" = [10.0, 10, 0.0] - -# Manually checked -"HONDA_CIVIC_2022" = [2.5, 1.2, 0.15] -"HONDA_HRV_3G" = [2.5, 1.2, 0.2] diff --git a/selfdrive/car/toyota/__init__.py b/selfdrive/car/toyota/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/toyota/fingerprints.py b/selfdrive/car/toyota/fingerprints.py deleted file mode 100644 index 292be96fc85e73..00000000000000 --- a/selfdrive/car/toyota/fingerprints.py +++ /dev/null @@ -1,1697 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.toyota.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.TOYOTA_AVALON: { - (Ecu.abs, 0x7b0, None): [ - b'F152607060\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510701300\x00\x00\x00\x00', - b'881510705100\x00\x00\x00\x00', - b'881510705200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41051\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0701100\x00\x00\x00\x00', - b'8646F0703000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_AVALON_2019: { - (Ecu.abs, 0x7b0, None): [ - b'F152607110\x00\x00\x00\x00\x00\x00', - b'F152607140\x00\x00\x00\x00\x00\x00', - b'F152607171\x00\x00\x00\x00\x00\x00', - b'F152607180\x00\x00\x00\x00\x00\x00', - b'F152641040\x00\x00\x00\x00\x00\x00', - b'F152641050\x00\x00\x00\x00\x00\x00', - b'F152641060\x00\x00\x00\x00\x00\x00', - b'F152641061\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510703200\x00\x00\x00\x00', - b'881510704200\x00\x00\x00\x00', - b'881514107100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B07010\x00\x00\x00\x00\x00\x00', - b'8965B41070\x00\x00\x00\x00\x00\x00', - b'8965B41080\x00\x00\x00\x00\x00\x00', - b'8965B41090\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630725100\x00\x00\x00\x00', - b'\x01896630725200\x00\x00\x00\x00', - b'\x01896630725300\x00\x00\x00\x00', - b'\x01896630725400\x00\x00\x00\x00', - b'\x01896630735100\x00\x00\x00\x00', - b'\x01896630738000\x00\x00\x00\x00', - b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630734000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0702100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_AVALON_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F152607240\x00\x00\x00\x00\x00\x00', - b'\x01F152607250\x00\x00\x00\x00\x00\x00', - b'\x01F152607280\x00\x00\x00\x00\x00\x00', - b'F152641080\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41110\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x01896630742000\x00\x00\x00\x00', - b'\x01896630743000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_CAMRY: { - (Ecu.engine, 0x700, None): [ - b'\x018966306L3100\x00\x00\x00\x00', - b'\x018966306L4200\x00\x00\x00\x00', - b'\x018966306L5200\x00\x00\x00\x00', - b'\x018966306L9000\x00\x00\x00\x00', - b'\x018966306P8000\x00\x00\x00\x00', - b'\x018966306Q3100\x00\x00\x00\x00', - b'\x018966306Q4000\x00\x00\x00\x00', - b'\x018966306Q4100\x00\x00\x00\x00', - b'\x018966306Q4200\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966333N1100\x00\x00\x00\x00', - b'\x018966333N4300\x00\x00\x00\x00', - b'\x018966333P3100\x00\x00\x00\x00', - b'\x018966333P3200\x00\x00\x00\x00', - b'\x018966333P4200\x00\x00\x00\x00', - b'\x018966333P4300\x00\x00\x00\x00', - b'\x018966333P4400\x00\x00\x00\x00', - b'\x018966333P4500\x00\x00\x00\x00', - b'\x018966333P4700\x00\x00\x00\x00', - b'\x018966333P4900\x00\x00\x00\x00', - b'\x018966333Q6000\x00\x00\x00\x00', - b'\x018966333Q6200\x00\x00\x00\x00', - b'\x018966333Q6300\x00\x00\x00\x00', - b'\x018966333Q6500\x00\x00\x00\x00', - b'\x018966333Q9200\x00\x00\x00\x00', - b'\x018966333W6000\x00\x00\x00\x00', - b'\x018966333X0000\x00\x00\x00\x00', - b'\x018966333X4000\x00\x00\x00\x00', - b'\x01896633T16000\x00\x00\x00\x00', - b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0601400 ', - b'8821F0601500 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604100 ', - b'8821F0604200 ', - b'8821F0605200 ', - b'8821F0606200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'8821F0608300 ', - b'8821F0609000 ', - b'8821F0609100 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606210\x00\x00\x00\x00\x00\x00', - b'F152606230\x00\x00\x00\x00\x00\x00', - b'F152606260\x00\x00\x00\x00\x00\x00', - b'F152606270\x00\x00\x00\x00\x00\x00', - b'F152606290\x00\x00\x00\x00\x00\x00', - b'F152606410\x00\x00\x00\x00\x00\x00', - b'F152633214\x00\x00\x00\x00\x00\x00', - b'F152633540\x00\x00\x00\x00\x00\x00', - b'F152633660\x00\x00\x00\x00\x00\x00', - b'F152633712\x00\x00\x00\x00\x00\x00', - b'F152633713\x00\x00\x00\x00\x00\x00', - b'F152633A10\x00\x00\x00\x00\x00\x00', - b'F152633A20\x00\x00\x00\x00\x00\x00', - b'F152633B51\x00\x00\x00\x00\x00\x00', - b'F152633B60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33540\x00\x00\x00\x00\x00\x00', - b'8965B33542\x00\x00\x00\x00\x00\x00', - b'8965B33550\x00\x00\x00\x00\x00\x00', - b'8965B33551\x00\x00\x00\x00\x00\x00', - b'8965B33580\x00\x00\x00\x00\x00\x00', - b'8965B33581\x00\x00\x00\x00\x00\x00', - b'8965B33611\x00\x00\x00\x00\x00\x00', - b'8965B33621\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0601400 ', - b'8821F0601500 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604100 ', - b'8821F0604200 ', - b'8821F0605200 ', - b'8821F0606200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'8821F0608300 ', - b'8821F0609000 ', - b'8821F0609100 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0601200 ', - b'8646F0601300 ', - b'8646F0601400 ', - b'8646F0603400 ', - b'8646F0603500 ', - b'8646F0604000 ', - b'8646F0604100 ', - b'8646F0605000 ', - b'8646F0606000 ', - b'8646F0606100 ', - b'8646F0607000 ', - b'8646F0607100 ', - ], - }, - CAR.TOYOTA_CAMRY_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B33630\x00\x00\x00\x00\x00\x00', - b'8965B33640\x00\x00\x00\x00\x00\x00', - b'8965B33650\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606370\x00\x00\x00\x00\x00\x00', - b'\x01F152606390\x00\x00\x00\x00\x00\x00', - b'\x01F152606400\x00\x00\x00\x00\x00\x00', - b'\x01F152606431\x00\x00\x00\x00\x00\x00', - b'\x01F152633E11\x00\x00\x00\x00\x00\x00', - b'F152633310\x00\x00\x00\x00\x00\x00', - b'F152633D00\x00\x00\x00\x00\x00\x00', - b'F152633D60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x018966306Q5000\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966306Q7000\x00\x00\x00\x00', - b'\x018966306Q9000\x00\x00\x00\x00', - b'\x018966306R3000\x00\x00\x00\x00', - b'\x018966306R8000\x00\x00\x00\x00', - b'\x018966306T0000\x00\x00\x00\x00', - b'\x018966306T3100\x00\x00\x00\x00', - b'\x018966306T3200\x00\x00\x00\x00', - b'\x018966306T4000\x00\x00\x00\x00', - b'\x018966306T4100\x00\x00\x00\x00', - b'\x018966306V1000\x00\x00\x00\x00', - b'\x018966333Z1000\x00\x00\x00\x00', - b'\x01896633T20000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F0602300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F3305300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F3305400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305500\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_CHR: { - (Ecu.engine, 0x700, None): [ - b'\x01896631017100\x00\x00\x00\x00', - b'\x01896631017200\x00\x00\x00\x00', - b'\x01896631021100\x00\x00\x00\x00', - b'\x0189663F413100\x00\x00\x00\x00', - b'\x0189663F414100\x00\x00\x00\x00', - b'\x0189663F438000\x00\x00\x00\x00', - b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405000 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152610012\x00\x00\x00\x00\x00\x00', - b'F152610013\x00\x00\x00\x00\x00\x00', - b'F152610014\x00\x00\x00\x00\x00\x00', - b'F152610020\x00\x00\x00\x00\x00\x00', - b'F152610040\x00\x00\x00\x00\x00\x00', - b'F152610153\x00\x00\x00\x00\x00\x00', - b'F152610190\x00\x00\x00\x00\x00\x00', - b'F152610200\x00\x00\x00\x00\x00\x00', - b'F152610210\x00\x00\x00\x00\x00\x00', - b'F152610220\x00\x00\x00\x00\x00\x00', - b'F152610230\x00\x00\x00\x00\x00\x00', - b'F1526F4034\x00\x00\x00\x00\x00\x00', - b'F1526F4044\x00\x00\x00\x00\x00\x00', - b'F1526F4073\x00\x00\x00\x00\x00\x00', - b'F1526F4121\x00\x00\x00\x00\x00\x00', - b'F1526F4122\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10011\x00\x00\x00\x00\x00\x00', - b'8965B10020\x00\x00\x00\x00\x00\x00', - b'8965B10040\x00\x00\x00\x00\x00\x00', - b'8965B10050\x00\x00\x00\x00\x00\x00', - b'8965B10070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x0331036000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', - b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405000 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646FF401700 ', - b'8646FF401800 ', - b'8646FF402100 ', - b'8646FF404000 ', - b'8646FF406000 ', - b'8646FF407000 ', - b'8646FF407100 ', - ], - }, - CAR.TOYOTA_CHR_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'F152610041\x00\x00\x00\x00\x00\x00', - b'F152610260\x00\x00\x00\x00\x00\x00', - b'F1526F4270\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10091\x00\x00\x00\x00\x00\x00', - b'8965B10092\x00\x00\x00\x00\x00\x00', - b'8965B10110\x00\x00\x00\x00\x00\x00', - b'8965B10111\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x0189663F438000\x00\x00\x00\x00', - b'\x0189663F459000\x00\x00\x00\x00', - b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821FF410200\x00\x00\x00\x00', - b'\x018821FF410300\x00\x00\x00\x00', - b'\x018821FF410400\x00\x00\x00\x00', - b'\x018821FF410500\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', - b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', - b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_COROLLA: { - (Ecu.engine, 0x7e0, None): [ - b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510201100\x00\x00\x00\x00', - b'881510201200\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152602190\x00\x00\x00\x00\x00\x00', - b'F152602191\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B02181\x00\x00\x00\x00\x00\x00', - b'8965B02191\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0201101\x00\x00\x00\x00', - b'8646F0201200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_COROLLA_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630A22000\x00\x00\x00\x00', - b'\x01896630ZG2000\x00\x00\x00\x00', - b'\x01896630ZG5000\x00\x00\x00\x00', - b'\x01896630ZG5100\x00\x00\x00\x00', - b'\x01896630ZG5200\x00\x00\x00\x00', - b'\x01896630ZG5300\x00\x00\x00\x00', - b'\x01896630ZJ1000\x00\x00\x00\x00', - b'\x01896630ZP1000\x00\x00\x00\x00', - b'\x01896630ZP2000\x00\x00\x00\x00', - b'\x01896630ZQ5000\x00\x00\x00\x00', - b'\x01896630ZU8000\x00\x00\x00\x00', - b'\x01896630ZU9000\x00\x00\x00\x00', - b'\x01896630ZX4000\x00\x00\x00\x00', - b'\x01896630ZX7100\x00\x00\x00\x00', - b'\x018966312L8000\x00\x00\x00\x00', - b'\x018966312M0000\x00\x00\x00\x00', - b'\x018966312M9000\x00\x00\x00\x00', - b'\x018966312P9000\x00\x00\x00\x00', - b'\x018966312P9100\x00\x00\x00\x00', - b'\x018966312P9200\x00\x00\x00\x00', - b'\x018966312P9300\x00\x00\x00\x00', - b'\x018966312Q2300\x00\x00\x00\x00', - b'\x018966312Q8000\x00\x00\x00\x00', - b'\x018966312R0000\x00\x00\x00\x00', - b'\x018966312R0100\x00\x00\x00\x00', - b'\x018966312R0200\x00\x00\x00\x00', - b'\x018966312R1000\x00\x00\x00\x00', - b'\x018966312R1100\x00\x00\x00\x00', - b'\x018966312R3100\x00\x00\x00\x00', - b'\x018966312S5000\x00\x00\x00\x00', - b'\x018966312S7000\x00\x00\x00\x00', - b'\x018966312W3000\x00\x00\x00\x00', - b'\x018966312W9000\x00\x00\x00\x00', - b'\x01896637621000\x00\x00\x00\x00', - b'\x01896637623000\x00\x00\x00\x00', - b'\x01896637624000\x00\x00\x00\x00', - b'\x01896637626000\x00\x00\x00\x00', - b'\x01896637639000\x00\x00\x00\x00', - b'\x01896637643000\x00\x00\x00\x00', - b'\x01896637644000\x00\x00\x00\x00', - b'\x01896637648000\x00\x00\x00\x00', - b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', - b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x038966312T3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZN5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x018965B12350\x00\x00\x00\x00\x00\x00', - b'\x018965B12470\x00\x00\x00\x00\x00\x00', - b'\x018965B12490\x00\x00\x00\x00\x00\x00', - b'\x018965B12500\x00\x00\x00\x00\x00\x00', - b'\x018965B12510\x00\x00\x00\x00\x00\x00', - b'\x018965B12520\x00\x00\x00\x00\x00\x00', - b'\x018965B12530\x00\x00\x00\x00\x00\x00', - b'\x018965B1254000\x00\x00\x00\x00', - b'\x018965B1255000\x00\x00\x00\x00', - b'\x018965B1256000\x00\x00\x00\x00', - b'\x018965B1270000\x00\x00\x00\x00', - b'8965B12361\x00\x00\x00\x00\x00\x00', - b'8965B12451\x00\x00\x00\x00\x00\x00', - b'8965B16011\x00\x00\x00\x00\x00\x00', - b'8965B16101\x00\x00\x00\x00\x00\x00', - b'8965B16170\x00\x00\x00\x00\x00\x00', - b'8965B76012\x00\x00\x00\x00\x00\x00', - b'8965B76050\x00\x00\x00\x00\x00\x00', - b'8965B76091\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152602280\x00\x00\x00\x00\x00\x00', - b'\x01F152602281\x00\x00\x00\x00\x00\x00', - b'\x01F152602470\x00\x00\x00\x00\x00\x00', - b'\x01F152602560\x00\x00\x00\x00\x00\x00', - b'\x01F152602590\x00\x00\x00\x00\x00\x00', - b'\x01F152602650\x00\x00\x00\x00\x00\x00', - b'\x01F15260A010\x00\x00\x00\x00\x00\x00', - b'\x01F15260A050\x00\x00\x00\x00\x00\x00', - b'\x01F15260A070\x00\x00\x00\x00\x00\x00', - b'\x01F152612641\x00\x00\x00\x00\x00\x00', - b'\x01F152612651\x00\x00\x00\x00\x00\x00', - b'\x01F152612862\x00\x00\x00\x00\x00\x00', - b'\x01F152612B10\x00\x00\x00\x00\x00\x00', - b'\x01F152612B51\x00\x00\x00\x00\x00\x00', - b'\x01F152612B60\x00\x00\x00\x00\x00\x00', - b'\x01F152612B61\x00\x00\x00\x00\x00\x00', - b'\x01F152612B62\x00\x00\x00\x00\x00\x00', - b'\x01F152612B70\x00\x00\x00\x00\x00\x00', - b'\x01F152612B71\x00\x00\x00\x00\x00\x00', - b'\x01F152612B81\x00\x00\x00\x00\x00\x00', - b'\x01F152612B90\x00\x00\x00\x00\x00\x00', - b'\x01F152612B91\x00\x00\x00\x00\x00\x00', - b'\x01F152612C00\x00\x00\x00\x00\x00\x00', - b'\x01F152676250\x00\x00\x00\x00\x00\x00', - b'F152612590\x00\x00\x00\x00\x00\x00', - b'F152612691\x00\x00\x00\x00\x00\x00', - b'F152612692\x00\x00\x00\x00\x00\x00', - b'F152612700\x00\x00\x00\x00\x00\x00', - b'F152612710\x00\x00\x00\x00\x00\x00', - b'F152612790\x00\x00\x00\x00\x00\x00', - b'F152612800\x00\x00\x00\x00\x00\x00', - b'F152612820\x00\x00\x00\x00\x00\x00', - b'F152612840\x00\x00\x00\x00\x00\x00', - b'F152612842\x00\x00\x00\x00\x00\x00', - b'F152612890\x00\x00\x00\x00\x00\x00', - b'F152612A00\x00\x00\x00\x00\x00\x00', - b'F152612A10\x00\x00\x00\x00\x00\x00', - b'F152612D00\x00\x00\x00\x00\x00\x00', - b'F152616011\x00\x00\x00\x00\x00\x00', - b'F152616030\x00\x00\x00\x00\x00\x00', - b'F152616060\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152676293\x00\x00\x00\x00\x00\x00', - b'F152676303\x00\x00\x00\x00\x00\x00', - b'F152676304\x00\x00\x00\x00\x00\x00', - b'F152676371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F12010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1206000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7603300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_HIGHLANDER: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E09000\x00\x00\x00\x00', - b'\x01896630E43000\x00\x00\x00\x00', - b'\x01896630E43100\x00\x00\x00\x00', - b'\x01896630E43200\x00\x00\x00\x00', - b'\x01896630E44200\x00\x00\x00\x00', - b'\x01896630E44400\x00\x00\x00\x00', - b'\x01896630E45000\x00\x00\x00\x00', - b'\x01896630E45100\x00\x00\x00\x00', - b'\x01896630E45200\x00\x00\x00\x00', - b'\x01896630E46000\x00\x00\x00\x00', - b'\x01896630E46200\x00\x00\x00\x00', - b'\x01896630E74000\x00\x00\x00\x00', - b'\x01896630E75000\x00\x00\x00\x00', - b'\x01896630E76000\x00\x00\x00\x00', - b'\x01896630E77000\x00\x00\x00\x00', - b'\x01896630E83000\x00\x00\x00\x00', - b'\x01896630E84000\x00\x00\x00\x00', - b'\x01896630E85000\x00\x00\x00\x00', - b'\x01896630E86000\x00\x00\x00\x00', - b'\x01896630E88000\x00\x00\x00\x00', - b'\x01896630EA0000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E51000\x00\x00\x00\x00\x00\x00\x00\x0050E17000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48140\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - b'8965B48160\x00\x00\x00\x00\x00\x00', - b'8965B48210\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260E011\x00\x00\x00\x00\x00\x00', - b'F152648541\x00\x00\x00\x00\x00\x00', - b'F152648542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510E01100\x00\x00\x00\x00', - b'881510E01200\x00\x00\x00\x00', - b'881510E02100\x00\x00\x00\x00', - b'881510E02200\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0E01200\x00\x00\x00\x00', - b'8646F0E01300\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_HIGHLANDER_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B48241\x00\x00\x00\x00\x00\x00', - b'8965B48310\x00\x00\x00\x00\x00\x00', - b'8965B48320\x00\x00\x00\x00\x00\x00', - b'8965B48400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E051\x00\x00\x00\x00\x00\x00', - b'\x01F15260E05300\x00\x00\x00\x00', - b'\x01F15260E061\x00\x00\x00\x00\x00\x00', - b'\x01F15260E110\x00\x00\x00\x00\x00\x00', - b'\x01F15260E170\x00\x00\x00\x00\x00\x00', - b'\x01F15264872300\x00\x00\x00\x00', - b'\x01F15264872400\x00\x00\x00\x00', - b'\x01F15264872500\x00\x00\x00\x00', - b'\x01F15264872600\x00\x00\x00\x00', - b'\x01F15264872700\x00\x00\x00\x00', - b'\x01F15264873500\x00\x00\x00\x00', - b'\x01F152648C6300\x00\x00\x00\x00', - b'\x01F152648J4000\x00\x00\x00\x00', - b'\x01F152648J5000\x00\x00\x00\x00', - b'\x01F152648J6000\x00\x00\x00\x00', - b'\x01F152648J7000\x00\x00\x00\x00', - b'\x01F152648L5000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630E62100\x00\x00\x00\x00', - b'\x01896630E62200\x00\x00\x00\x00', - b'\x01896630E64100\x00\x00\x00\x00', - b'\x01896630E64200\x00\x00\x00\x00', - b'\x01896630E64400\x00\x00\x00\x00', - b'\x01896630E67000\x00\x00\x00\x00', - b'\x01896630EA1000\x00\x00\x00\x00', - b'\x01896630EB1000\x00\x00\x00\x00', - b'\x01896630EB1100\x00\x00\x00\x00', - b'\x01896630EB1200\x00\x00\x00\x00', - b'\x01896630EB1300\x00\x00\x00\x00', - b'\x01896630EB2000\x00\x00\x00\x00', - b'\x01896630EB2100\x00\x00\x00\x00', - b'\x01896630EB2200\x00\x00\x00\x00', - b'\x01896630EC4000\x00\x00\x00\x00', - b'\x01896630ED9000\x00\x00\x00\x00', - b'\x01896630ED9100\x00\x00\x00\x00', - b'\x01896630EE1000\x00\x00\x00\x00', - b'\x01896630EE1100\x00\x00\x00\x00', - b'\x01896630EE4000\x00\x00\x00\x00', - b'\x01896630EE4100\x00\x00\x00\x00', - b'\x01896630EE5000\x00\x00\x00\x00', - b'\x01896630EE6000\x00\x00\x00\x00', - b'\x01896630EE7000\x00\x00\x00\x00', - b'\x01896630EF8000\x00\x00\x00\x00', - b'\x01896630EG3000\x00\x00\x00\x00', - b'\x01896630EG5000\x00\x00\x00\x00', - b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS: { - (Ecu.engine, 0x700, None): [ - b'\x018966353M7000\x00\x00\x00\x00', - b'\x018966353M7100\x00\x00\x00\x00', - b'\x018966353Q2000\x00\x00\x00\x00', - b'\x018966353Q2100\x00\x00\x00\x00', - b'\x018966353Q2300\x00\x00\x00\x00', - b'\x018966353Q4000\x00\x00\x00\x00', - b'\x018966353R1100\x00\x00\x00\x00', - b'\x018966353R7100\x00\x00\x00\x00', - b'\x018966353R8000\x00\x00\x00\x00', - b'\x018966353R8100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152653300\x00\x00\x00\x00\x00\x00', - b'F152653301\x00\x00\x00\x00\x00\x00', - b'F152653310\x00\x00\x00\x00\x00\x00', - b'F152653330\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881515306200\x00\x00\x00\x00', - b'881515306400\x00\x00\x00\x00', - b'881515306500\x00\x00\x00\x00', - b'881515307400\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53270\x00\x00\x00\x00\x00\x00', - b'8965B53271\x00\x00\x00\x00\x00\x00', - b'8965B53280\x00\x00\x00\x00\x00\x00', - b'8965B53281\x00\x00\x00\x00\x00\x00', - b'8965B53311\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F5301101\x00\x00\x00\x00', - b'8646F5301200\x00\x00\x00\x00', - b'8646F5301300\x00\x00\x00\x00', - b'8646F5301400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966353S1000\x00\x00\x00\x00', - b'\x018966353S2000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02353U0000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15265337200\x00\x00\x00\x00', - b'\x01F15265342000\x00\x00\x00\x00', - b'\x01F15265343000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53450\x00\x00\x00\x00\x00\x00', - b'8965B53800\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F5303300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS: { - (Ecu.engine, 0x700, None): [ - b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', - b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47021\x00\x00\x00\x00\x00\x00', - b'8965B47022\x00\x00\x00\x00\x00\x00', - b'8965B47023\x00\x00\x00\x00\x00\x00', - b'8965B47050\x00\x00\x00\x00\x00\x00', - b'8965B47060\x00\x00\x00\x00\x00\x00', - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647290\x00\x00\x00\x00\x00\x00', - b'F152647300\x00\x00\x00\x00\x00\x00', - b'F152647310\x00\x00\x00\x00\x00\x00', - b'F152647414\x00\x00\x00\x00\x00\x00', - b'F152647415\x00\x00\x00\x00\x00\x00', - b'F152647416\x00\x00\x00\x00\x00\x00', - b'F152647417\x00\x00\x00\x00\x00\x00', - b'F152647470\x00\x00\x00\x00\x00\x00', - b'F152647490\x00\x00\x00\x00\x00\x00', - b'F152647682\x00\x00\x00\x00\x00\x00', - b'F152647683\x00\x00\x00\x00\x00\x00', - b'F152647684\x00\x00\x00\x00\x00\x00', - b'F152647862\x00\x00\x00\x00\x00\x00', - b'F152647863\x00\x00\x00\x00\x00\x00', - b'F152647864\x00\x00\x00\x00\x00\x00', - b'F152647865\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514702300\x00\x00\x00\x00', - b'881514702400\x00\x00\x00\x00', - b'881514703100\x00\x00\x00\x00', - b'881514704100\x00\x00\x00\x00', - b'881514706000\x00\x00\x00\x00', - b'881514706100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4701300\x00\x00\x00\x00', - b'8646F4702001\x00\x00\x00\x00', - b'8646F4702100\x00\x00\x00\x00', - b'8646F4702200\x00\x00\x00\x00', - b'8646F4705000\x00\x00\x00\x00', - b'8646F4705200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS_V: { - (Ecu.abs, 0x7b0, None): [ - b'F152647280\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514705100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4703300\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42063\x00\x00\x00\x00\x00\x00', - b'8965B42073\x00\x00\x00\x00\x00\x00', - b'8965B42082\x00\x00\x00\x00\x00\x00', - b'8965B42083\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260R102\x00\x00\x00\x00\x00\x00', - b'F15260R103\x00\x00\x00\x00\x00\x00', - b'F152642492\x00\x00\x00\x00\x00\x00', - b'F152642493\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514201200\x00\x00\x00\x00', - b'881514201300\x00\x00\x00\x00', - b'881514201400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4H: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42102\x00\x00\x00\x00\x00\x00', - b'8965B42103\x00\x00\x00\x00\x00\x00', - b'8965B42112\x00\x00\x00\x00\x00\x00', - b'8965B42162\x00\x00\x00\x00\x00\x00', - b'8965B42163\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152642090\x00\x00\x00\x00\x00\x00', - b'F152642110\x00\x00\x00\x00\x00\x00', - b'F152642120\x00\x00\x00\x00\x00\x00', - b'F152642400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514202200\x00\x00\x00\x00', - b'881514202300\x00\x00\x00\x00', - b'881514202400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630R58000\x00\x00\x00\x00', - b'\x01896630R58100\x00\x00\x00\x00', - b'\x018966342E2000\x00\x00\x00\x00', - b'\x018966342M5000\x00\x00\x00\x00', - b'\x018966342M8000\x00\x00\x00\x00', - b'\x018966342S9000\x00\x00\x00\x00', - b'\x018966342T1000\x00\x00\x00\x00', - b'\x018966342T6000\x00\x00\x00\x00', - b'\x018966342T9000\x00\x00\x00\x00', - b'\x018966342U4000\x00\x00\x00\x00', - b'\x018966342U4100\x00\x00\x00\x00', - b'\x018966342U5100\x00\x00\x00\x00', - b'\x018966342V0000\x00\x00\x00\x00', - b'\x018966342V3000\x00\x00\x00\x00', - b'\x018966342V3100\x00\x00\x00\x00', - b'\x018966342V3200\x00\x00\x00\x00', - b'\x018966342W5000\x00\x00\x00\x00', - b'\x018966342W7000\x00\x00\x00\x00', - b'\x018966342W8000\x00\x00\x00\x00', - b'\x018966342X5000\x00\x00\x00\x00', - b'\x018966342X6000\x00\x00\x00\x00', - b'\x01896634A05000\x00\x00\x00\x00', - b'\x01896634A15000\x00\x00\x00\x00', - b'\x01896634A19000\x00\x00\x00\x00', - b'\x01896634A19100\x00\x00\x00\x00', - b'\x01896634A20000\x00\x00\x00\x00', - b'\x01896634A20100\x00\x00\x00\x00', - b'\x01896634A22000\x00\x00\x00\x00', - b'\x01896634A22100\x00\x00\x00\x00', - b'\x01896634A25000\x00\x00\x00\x00', - b'\x01896634A30000\x00\x00\x00\x00', - b'\x01896634A44000\x00\x00\x00\x00', - b'\x01896634A45000\x00\x00\x00\x00', - b'\x01896634A46000\x00\x00\x00\x00', - b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', - b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13201\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF0R01000\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R210\x00\x00\x00\x00\x00\x00', - b'\x01F15260R220\x00\x00\x00\x00\x00\x00', - b'\x01F15260R290\x00\x00\x00\x00\x00\x00', - b'\x01F15260R292\x00\x00\x00\x00\x00\x00', - b'\x01F15260R300\x00\x00\x00\x00\x00\x00', - b'\x01F15260R302\x00\x00\x00\x00\x00\x00', - b'\x01F152642551\x00\x00\x00\x00\x00\x00', - b'\x01F152642561\x00\x00\x00\x00\x00\x00', - b'\x01F152642601\x00\x00\x00\x00\x00\x00', - b'\x01F152642700\x00\x00\x00\x00\x00\x00', - b'\x01F152642701\x00\x00\x00\x00\x00\x00', - b'\x01F152642710\x00\x00\x00\x00\x00\x00', - b'\x01F152642711\x00\x00\x00\x00\x00\x00', - b'\x01F152642750\x00\x00\x00\x00\x00\x00', - b'\x01F152642751\x00\x00\x00\x00\x00\x00', - b'F152642290\x00\x00\x00\x00\x00\x00', - b'F152642291\x00\x00\x00\x00\x00\x00', - b'F152642322\x00\x00\x00\x00\x00\x00', - b'F152642330\x00\x00\x00\x00\x00\x00', - b'F152642331\x00\x00\x00\x00\x00\x00', - b'F152642520\x00\x00\x00\x00\x00\x00', - b'F152642521\x00\x00\x00\x00\x00\x00', - b'F152642531\x00\x00\x00\x00\x00\x00', - b'F152642532\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152642541\x00\x00\x00\x00\x00\x00', - b'F152642542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', - b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', - b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', - b'8965B42170\x00\x00\x00\x00\x00\x00', - b'8965B42171\x00\x00\x00\x00\x00\x00', - b'8965B42180\x00\x00\x00\x00\x00\x00', - b'8965B42181\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R350\x00\x00\x00\x00\x00\x00', - b'\x01F15260R361\x00\x00\x00\x00\x00\x00', - b'\x01F15264283100\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264286100\x00\x00\x00\x00', - b'\x01F15264286200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', - b'8965B42172\x00\x00\x00\x00\x00\x00', - b'8965B42182\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A02001\x00\x00\x00\x00', - b'\x01896634A03000\x00\x00\x00\x00', - b'\x01896634A08000\x00\x00\x00\x00', - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A62000\x00\x00\x00\x00', - b'\x01896634A62100\x00\x00\x00\x00', - b'\x01896634A63000\x00\x00\x00\x00', - b'\x01896634A88000\x00\x00\x00\x00', - b'\x01896634A89000\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AA0000\x00\x00\x00\x00', - b'\x01896634AA0100\x00\x00\x00\x00', - b'\x01896634AA1000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R01100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R440\x00\x00\x00\x00\x00\x00', - b'\x01F15260R450\x00\x00\x00\x00\x00\x00', - b'\x01F15260R50000\x00\x00\x00\x00', - b'\x01F15260R51000\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264283300\x00\x00\x00\x00', - b'\x01F152642F1000\x00\x00\x00\x00', - b'\x01F152642F8000\x00\x00\x00\x00', - b'\x01F152642F8100\x00\x00\x00\x00', - b'\x01F152642F9000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', - b'8965B42371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A88100\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AE1001\x00\x00\x00\x00', - b'\x01896634AF0000\x00\x00\x00\x00', - b'\x01896634AJ2000\x00\x00\x00\x00', - b'\x01896634AJ3000\x00\x00\x00\x00', - b'\x01896634AL5000\x00\x00\x00\x00', - b'\x01896634AL6000\x00\x00\x00\x00', - b'\x01896634AL8000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R03100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', - b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', - b'\x028646F0R11000\x00\x00\x00\x008646G0R04000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_SIENNA: { - (Ecu.engine, 0x700, None): [ - b'\x01896630832100\x00\x00\x00\x00', - b'\x01896630832200\x00\x00\x00\x00', - b'\x01896630838000\x00\x00\x00\x00', - b'\x01896630838100\x00\x00\x00\x00', - b'\x01896630842000\x00\x00\x00\x00', - b'\x01896630843000\x00\x00\x00\x00', - b'\x01896630851000\x00\x00\x00\x00', - b'\x01896630851100\x00\x00\x00\x00', - b'\x01896630851200\x00\x00\x00\x00', - b'\x01896630852000\x00\x00\x00\x00', - b'\x01896630852100\x00\x00\x00\x00', - b'\x01896630859000\x00\x00\x00\x00', - b'\x01896630860000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B45070\x00\x00\x00\x00\x00\x00', - b'8965B45080\x00\x00\x00\x00\x00\x00', - b'8965B45082\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152608130\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510801100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702200\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0801100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_CTH: { - (Ecu.dsu, 0x791, None): [ - b'881517601100\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152676144\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237635000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7601100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966306U6000\x00\x00\x00\x00', - b'\x018966333T5000\x00\x00\x00\x00', - b'\x018966333T5100\x00\x00\x00\x00', - b'\x018966333X6000\x00\x00\x00\x00', - b'\x01896633T07000\x00\x00\x00\x00', - b'\x01896633T38000\x00\x00\x00\x00', - b'\x01896633T58000\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - b'\x02896633T10000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606281\x00\x00\x00\x00\x00\x00', - b'\x01F152606340\x00\x00\x00\x00\x00\x00', - b'\x01F152606461\x00\x00\x00\x00\x00\x00', - b'\x01F15260646200\x00\x00\x00\x00', - b'F152633423\x00\x00\x00\x00\x00\x00', - b'F152633680\x00\x00\x00\x00\x00\x00', - b'F152633681\x00\x00\x00\x00\x00\x00', - b'F152633F50\x00\x00\x00\x00\x00\x00', - b'F152633F51\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33252\x00\x00\x00\x00\x00\x00', - b'8965B33590\x00\x00\x00\x00\x00\x00', - b'8965B33690\x00\x00\x00\x00\x00\x00', - b'8965B33721\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES: { - (Ecu.engine, 0x7e0, None): [ - b'\x02333M4100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606202\x00\x00\x00\x00\x00\x00', - b'F152633171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513309400\x00\x00\x00\x00', - b'881513309500\x00\x00\x00\x00', - b'881513310400\x00\x00\x00\x00', - b'881513310500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33502\x00\x00\x00\x00\x00\x00', - b'8965B33512\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3302001\x00\x00\x00\x00', - b'8646F3302100\x00\x00\x00\x00', - b'8646F3302200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_GS_F: { - (Ecu.engine, 0x7e0, None): [ - b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152630700\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513016200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B30551\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3002100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX: { - (Ecu.engine, 0x700, None): [ - b'\x01896637850000\x00\x00\x00\x00', - b'\x01896637851000\x00\x00\x00\x00', - b'\x01896637852000\x00\x00\x00\x00', - b'\x01896637854000\x00\x00\x00\x00', - b'\x01896637873000\x00\x00\x00\x00', - b'\x01896637878000\x00\x00\x00\x00', - b'\x01896637878100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152678130\x00\x00\x00\x00\x00\x00', - b'F152678140\x00\x00\x00\x00\x00\x00', - b'F152678160\x00\x00\x00\x00\x00\x00', - b'F152678170\x00\x00\x00\x00\x00\x00', - b'F152678171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881517803100\x00\x00\x00\x00', - b'881517803300\x00\x00\x00\x00', - b'881517804100\x00\x00\x00\x00', - b'881517804300\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78060\x00\x00\x00\x00\x00\x00', - b'8965B78080\x00\x00\x00\x00\x00\x00', - b'8965B78100\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7801100\x00\x00\x00\x00', - b'8646F7801300\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966378B2000\x00\x00\x00\x00', - b'\x018966378B2100\x00\x00\x00\x00', - b'\x018966378B3000\x00\x00\x00\x00', - b'\x018966378B3100\x00\x00\x00\x00', - b'\x018966378B4100\x00\x00\x00\x00', - b'\x018966378G2000\x00\x00\x00\x00', - b'\x018966378G3000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237881000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152678221\x00\x00\x00\x00\x00\x00', - b'F152678200\x00\x00\x00\x00\x00\x00', - b'F152678210\x00\x00\x00\x00\x00\x00', - b'F152678211\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78110\x00\x00\x00\x00\x00\x00', - b'8965B78120\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_LC_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0131130000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152611390\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B11091\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F1104200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F1105200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RC: { - (Ecu.engine, 0x700, None): [ - b'\x01896632461100\x00\x00\x00\x00', - b'\x01896632478100\x00\x00\x00\x00', - b'\x01896632478200\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152624150\x00\x00\x00\x00\x00\x00', - b'F152624221\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881512404100\x00\x00\x00\x00', - b'881512407000\x00\x00\x00\x00', - b'881512409100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B24081\x00\x00\x00\x00\x00\x00', - b'8965B24240\x00\x00\x00\x00\x00\x00', - b'8965B24320\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F2401100\x00\x00\x00\x00', - b'8646F2401200\x00\x00\x00\x00', - b'8646F2402200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E36100\x00\x00\x00\x00', - b'\x01896630E36200\x00\x00\x00\x00', - b'\x01896630E36300\x00\x00\x00\x00', - b'\x01896630E37100\x00\x00\x00\x00', - b'\x01896630E37200\x00\x00\x00\x00', - b'\x01896630E37300\x00\x00\x00\x00', - b'\x01896630E41000\x00\x00\x00\x00', - b'\x01896630E41100\x00\x00\x00\x00', - b'\x01896630E41200\x00\x00\x00\x00', - b'\x01896630E41500\x00\x00\x00\x00', - b'\x01896630EA3100\x00\x00\x00\x00', - b'\x01896630EA3300\x00\x00\x00\x00', - b'\x01896630EA3400\x00\x00\x00\x00', - b'\x01896630EA4100\x00\x00\x00\x00', - b'\x01896630EA4200\x00\x00\x00\x00', - b'\x01896630EA4300\x00\x00\x00\x00', - b'\x01896630EA4400\x00\x00\x00\x00', - b'\x01896630EA6300\x00\x00\x00\x00', - b'\x018966348R1300\x00\x00\x00\x00', - b'\x018966348R8500\x00\x00\x00\x00', - b'\x018966348R9300\x00\x00\x00\x00', - b'\x018966348W1300\x00\x00\x00\x00', - b'\x018966348W2300\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02348J7000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Q4100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1200\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152648361\x00\x00\x00\x00\x00\x00', - b'F152648472\x00\x00\x00\x00\x00\x00', - b'F152648473\x00\x00\x00\x00\x00\x00', - b'F152648474\x00\x00\x00\x00\x00\x00', - b'F152648492\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - b'F152648494\x00\x00\x00\x00\x00\x00', - b'F152648501\x00\x00\x00\x00\x00\x00', - b'F152648502\x00\x00\x00\x00\x00\x00', - b'F152648504\x00\x00\x00\x00\x00\x00', - b'F152648630\x00\x00\x00\x00\x00\x00', - b'F152648740\x00\x00\x00\x00\x00\x00', - b'F152648A30\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514810300\x00\x00\x00\x00', - b'881514810500\x00\x00\x00\x00', - b'881514810700\x00\x00\x00\x00', - b'881514811300\x00\x00\x00\x00', - b'881514811500\x00\x00\x00\x00', - b'881514811700\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B0E011\x00\x00\x00\x00\x00\x00', - b'8965B0E012\x00\x00\x00\x00\x00\x00', - b'8965B48102\x00\x00\x00\x00\x00\x00', - b'8965B48111\x00\x00\x00\x00\x00\x00', - b'8965B48112\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701000\x00\x00\x00\x00', - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4801100\x00\x00\x00\x00', - b'8646F4801200\x00\x00\x00\x00', - b'8646F4802001\x00\x00\x00\x00', - b'8646F4802100\x00\x00\x00\x00', - b'8646F4802200\x00\x00\x00\x00', - b'8646F4809000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630EA9000\x00\x00\x00\x00', - b'\x01896630EB0000\x00\x00\x00\x00', - b'\x01896630EC9000\x00\x00\x00\x00', - b'\x01896630EC9100\x00\x00\x00\x00', - b'\x01896630ED0000\x00\x00\x00\x00', - b'\x01896630ED0100\x00\x00\x00\x00', - b'\x01896630ED5000\x00\x00\x00\x00', - b'\x01896630ED6000\x00\x00\x00\x00', - b'\x018966348R9200\x00\x00\x00\x00', - b'\x018966348T8000\x00\x00\x00\x00', - b'\x018966348W5100\x00\x00\x00\x00', - b'\x018966348W9000\x00\x00\x00\x00', - b'\x018966348X0000\x00\x00\x00\x00', - b'\x01896634D11000\x00\x00\x00\x00', - b'\x01896634D12000\x00\x00\x00\x00', - b'\x01896634D12100\x00\x00\x00\x00', - b'\x01896634D43000\x00\x00\x00\x00', - b'\x01896634D44000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E031\x00\x00\x00\x00\x00\x00', - b'\x01F15260E041\x00\x00\x00\x00\x00\x00', - b'\x01F152648781\x00\x00\x00\x00\x00\x00', - b'\x01F152648801\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - b'F152648811\x00\x00\x00\x00\x00\x00', - b'F152648831\x00\x00\x00\x00\x00\x00', - b'F152648891\x00\x00\x00\x00\x00\x00', - b'F152648C80\x00\x00\x00\x00\x00\x00', - b'F152648D00\x00\x00\x00\x00\x00\x00', - b'F152648D60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48261\x00\x00\x00\x00\x00\x00', - b'8965B48271\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647500\x00\x00\x00\x00\x00\x00', - b'F152647510\x00\x00\x00\x00\x00\x00', - b'F152647520\x00\x00\x00\x00\x00\x00', - b'F152647521\x00\x00\x00\x00\x00\x00', - b'F152647531\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_MIRAI: { - (Ecu.abs, 0x7d1, None): [ - b'\x01898A36203000\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15266203200\x00\x00\x00\x00', - b'\x01F15266203500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_ALPHARD_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B58040\x00\x00\x00\x00\x00\x00', - b'8965B58052\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152658320\x00\x00\x00\x00\x00\x00', - b'F152658341\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py deleted file mode 100755 index fae6eecaf634e2..00000000000000 --- a/selfdrive/car/toyota/radar_interface.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.can.parser import CANParser -from cereal import car -from openpilot.selfdrive.car.toyota.values import DBC, TSS2_CAR -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - - -def _create_radar_can_parser(car_fingerprint): - if car_fingerprint in TSS2_CAR: - RADAR_A_MSGS = list(range(0x180, 0x190)) - RADAR_B_MSGS = list(range(0x190, 0x1a0)) - else: - RADAR_A_MSGS = list(range(0x210, 0x220)) - RADAR_B_MSGS = list(range(0x220, 0x230)) - - msg_a_n = len(RADAR_A_MSGS) - msg_b_n = len(RADAR_B_MSGS) - messages = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n), strict=True)) - - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.track_id = 0 - self.radar_ts = CP.radarTimeStep - - if CP.carFingerprint in TSS2_CAR: - self.RADAR_A_MSGS = list(range(0x180, 0x190)) - self.RADAR_B_MSGS = list(range(0x190, 0x1a0)) - else: - self.RADAR_A_MSGS = list(range(0x210, 0x220)) - self.RADAR_B_MSGS = list(range(0x220, 0x230)) - - self.valid_cnt = {key: 0 for key in self.RADAR_A_MSGS} - - self.rcp = None if CP.radarUnavailable else _create_radar_can_parser(CP.carFingerprint) - self.trigger_msg = self.RADAR_B_MSGS[-1] - self.updated_messages = set() - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for ii in sorted(updated_messages): - if ii in self.RADAR_A_MSGS: - cpt = self.rcp.vl[ii] - - if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: - self.valid_cnt[ii] = 0 # reset counter - if cpt['VALID'] and cpt['LONG_DIST'] < 255: - self.valid_cnt[ii] += 1 - else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - - score = self.rcp.vl[ii+16]['SCORE'] - # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] - - # radar point only valid if it's a valid measurement and score is above 50 - if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = bool(cpt['VALID']) - else: - if ii in self.pts: - del self.pts[ii] - - ret.points = list(self.pts.values()) - return ret diff --git a/selfdrive/car/toyota/tests/__init__.py b/selfdrive/car/toyota/tests/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/toyota/tests/print_platform_codes.py b/selfdrive/car/toyota/tests/print_platform_codes.py deleted file mode 100755 index 9ec7a14cd3eed0..00000000000000 --- a/selfdrive/car/toyota/tests/print_platform_codes.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict -from cereal import car -from openpilot.selfdrive.car.toyota.values import PLATFORM_CODE_ECUS, get_platform_codes -from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -if __name__ == "__main__": - parts_for_ecu: dict = defaultdict(set) - cars_for_code: dict = defaultdict(lambda: defaultdict(set)) - for car_model, ecus in FW_VERSIONS.items(): - print() - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - platform_codes = get_platform_codes(ecus[ecu]) - parts_for_ecu[ecu] |= {code.split(b'-')[0] for code in platform_codes if code.count(b'-') > 1} - for code in platform_codes: - cars_for_code[ecu][b'-'.join(code.split(b'-')[:2])] |= {car_model} - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {platform_codes}') - - print('\nECU parts:') - for ecu, parts in parts_for_ecu.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}): {parts}') - - print('\nCar models vs. platform codes (no major versions):') - for ecu, codes in cars_for_code.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - for code, cars in codes.items(): - print(f' {code!r}: {sorted(cars)}') diff --git a/selfdrive/car/toyota/tests/test_toyota.py b/selfdrive/car/toyota/tests/test_toyota.py deleted file mode 100644 index 75e3ea70378d87..00000000000000 --- a/selfdrive/car/toyota/tests/test_toyota.py +++ /dev/null @@ -1,167 +0,0 @@ -from hypothesis import given, settings, strategies as st - -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.toyota.values import CAR, DBC, TSS2_CAR, ANGLE_CONTROL_CAR, RADAR_ACC_CAR, \ - FW_QUERY_CONFIG, PLATFORM_CODE_ECUS, FUZZY_EXCLUDED_PLATFORMS, \ - get_platform_codes - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -def check_fw_version(fw_version: bytes) -> bool: - # TODO: just use the FW patterns, need to support all chunks - return b'?' not in fw_version and b'!' not in fw_version - - -class TestToyotaInterfaces: - def test_car_sets(self): - assert len(ANGLE_CONTROL_CAR - TSS2_CAR) == 0 - assert len(RADAR_ACC_CAR - TSS2_CAR) == 0 - - def test_lta_platforms(self): - # At this time, only RAV4 2023 is expected to use LTA/angle control - assert ANGLE_CONTROL_CAR == {CAR.TOYOTA_RAV4_TSS2_2023} - - def test_tss2_dbc(self): - # We make some assumptions about TSS2 platforms, - # like looking up certain signals only in this DBC - for car_model, dbc in DBC.items(): - if car_model in TSS2_CAR: - assert dbc["pt"] == "toyota_nodsu_pt_generated" - - def test_essential_ecus(self, subtests): - # Asserts standard ECUs exist for each platform - common_ecus = {Ecu.fwdRadar, Ecu.fwdCamera} - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - present_ecus = {ecu[0] for ecu in ecus} - missing_ecus = common_ecus - present_ecus - assert len(missing_ecus) == 0 - - # Some exceptions for other common ECUs - if car_model not in (CAR.TOYOTA_ALPHARD_TSS2,): - assert Ecu.abs in present_ecus - - if car_model not in (CAR.TOYOTA_MIRAI,): - assert Ecu.engine in present_ecus - - if car_model not in (CAR.TOYOTA_PRIUS_V, CAR.LEXUS_CTH): - assert Ecu.eps in present_ecus - - -class TestToyotaFingerprint: - def test_non_essential_ecus(self, subtests): - # Ensures only the cars that have multiple engine ECUs are in the engine non-essential ECU list - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - engine_ecus = {ecu for ecu in ecus if ecu[0] == Ecu.engine} - assert (len(engine_ecus) > 1) == (car_model in FW_QUERY_CONFIG.non_essential_ecus[Ecu.engine]), \ - f"Car model unexpectedly {'not ' if len(engine_ecus) > 1 else ''}in non-essential list" - - def test_valid_fw_versions(self, subtests): - # Asserts all FW versions are valid - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for fws in ecus.values(): - for fw in fws: - assert check_fw_version(fw), fw - - # Tests for part numbers, platform codes, and sub-versions which Toyota will use to fuzzy - # fingerprint in the absence of full FW matches: - @settings(max_examples=100) - @given(data=st.data()) - def test_platform_codes_fuzzy_fw(self, data): - fw_strategy = st.lists(st.binary()) - fws = data.draw(fw_strategy) - get_platform_codes(fws) - - def test_platform_code_ecus_available(self, subtests): - # Asserts ECU keys essential for fuzzy fingerprinting are available on all platforms - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for platform_code_ecu in PLATFORM_CODE_ECUS: - if platform_code_ecu == Ecu.eps and car_model in (CAR.TOYOTA_PRIUS_V, CAR.LEXUS_CTH,): - continue - if platform_code_ecu == Ecu.abs and car_model in (CAR.TOYOTA_ALPHARD_TSS2,): - continue - assert platform_code_ecu in [e[0] for e in ecus] - - def test_fw_format(self, subtests): - # Asserts: - # - every supported ECU FW version returns one platform code - # - every supported ECU FW version has a part number - # - expected parsing of ECU sub-versions - - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - codes = dict() - for fw in fws: - result = get_platform_codes([fw]) - # Check only one platform code and sub-version - assert 1 == len(result), f"Unable to parse FW: {fw}" - assert 1 == len(list(result.values())[0]), f"Unable to parse FW: {fw}" - codes |= result - - # Toyota places the ECU part number in their FW versions, assert all parsable - # Note that there is only one unique part number per ECU across the fleet, so this - # is not important for identification, just a sanity check. - assert all(code.count(b"-") > 1 for code in codes), f"FW does not have part number: {fw} {codes}" - - def test_platform_codes_spot_check(self): - # Asserts basic platform code parsing behavior for a few cases - results = get_platform_codes([ - b"F152607140\x00\x00\x00\x00\x00\x00", - b"F152607171\x00\x00\x00\x00\x00\x00", - b"F152607110\x00\x00\x00\x00\x00\x00", - b"F152607180\x00\x00\x00\x00\x00\x00", - ]) - assert results == {b"F1526-07-1": {b"10", b"40", b"71", b"80"}} - - results = get_platform_codes([ - b"\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00", - b"\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00", - ]) - assert results == {b"8646F-41-04": {b"100"}} - - # Short version has no part number - results = get_platform_codes([ - b"\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00", - b"\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00", - ]) - assert results == {b"58-70": {b"000"}, b"58-83": {b"000"}} - - results = get_platform_codes([ - b"F152607110\x00\x00\x00\x00\x00\x00", - b"F152607140\x00\x00\x00\x00\x00\x00", - b"\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00", - b"\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00", - ]) - assert results == {b"F1526-07-1": {b"10", b"40"}, b"8646F-41-04": {b"100"}, b"58-79": {b"000"}} - - def test_fuzzy_excluded_platforms(self): - # Asserts a list of platforms that will not fuzzy fingerprint with platform codes due to them being shared. - platforms_with_shared_codes = set() - for platform, fw_by_addr in FW_VERSIONS.items(): - car_fw = [] - for ecu, fw_versions in fw_by_addr.items(): - ecu_name, addr, sub_addr = ecu - for fw in fw_versions: - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) - - CP = car.CarParams.new_message(carFw=car_fw) - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) - if len(matches) == 1: - assert list(matches)[0] == platform - else: - # If a platform has multiple matches, add it and its matches - platforms_with_shared_codes |= {str(platform), *matches} - - assert platforms_with_shared_codes == FUZZY_EXCLUDED_PLATFORMS, (len(platforms_with_shared_codes), len(FW_VERSIONS)) diff --git a/selfdrive/car/values.py b/selfdrive/car/values.py deleted file mode 100644 index bf5d378ab4f58c..00000000000000 --- a/selfdrive/car/values.py +++ /dev/null @@ -1,19 +0,0 @@ -from typing import get_args -from openpilot.selfdrive.car.body.values import CAR as BODY -from openpilot.selfdrive.car.chrysler.values import CAR as CHRYSLER -from openpilot.selfdrive.car.ford.values import CAR as FORD -from openpilot.selfdrive.car.gm.values import CAR as GM -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.hyundai.values import CAR as HYUNDAI -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.subaru.values import CAR as SUBARU -from openpilot.selfdrive.car.tesla.values import CAR as TESLA -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.volkswagen.values import CAR as VOLKSWAGEN - -Platform = BODY | CHRYSLER | FORD | GM | HONDA | HYUNDAI | MAZDA | MOCK | NISSAN | SUBARU | TESLA | TOYOTA | VOLKSWAGEN -BRANDS = get_args(Platform) - -PLATFORMS: dict[str, Platform] = {str(platform): platform for brand in BRANDS for platform in brand} diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py deleted file mode 100755 index 9a667f3ced7065..00000000000000 --- a/selfdrive/car/vin.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python3 -import re - -from panda.python.uds import get_rx_addr_for_tx_addr, FUNCTIONAL_ADDRS -from openpilot.selfdrive.car import carlog -from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from openpilot.selfdrive.car.fw_query_definitions import STANDARD_VIN_ADDRS, StdQueries - -VIN_UNKNOWN = "0" * 17 -VIN_RE = "[A-HJ-NPR-Z0-9]{17}" - - -def is_valid_vin(vin: str): - return re.fullmatch(VIN_RE, vin) is not None - - -def get_vin(can_recv, can_send, buses, timeout=0.1, retry=2, debug=False): - for i in range(retry): - for bus in buses: - for request, response, valid_buses, vin_addrs, functional_addrs, rx_offset in ( - (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, FUNCTIONAL_ADDRS, 0x8), - (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, FUNCTIONAL_ADDRS, 0x8), - (StdQueries.GM_VIN_REQUEST, StdQueries.GM_VIN_RESPONSE, (0,), [0x24b], None, 0x400), # Bolt fwdCamera - (StdQueries.KWP_VIN_REQUEST, StdQueries.KWP_VIN_RESPONSE, (0,), [0x797], None, 0x3), # Nissan Leaf VCM - (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0,), [0x74f], None, 0x6a), # Volkswagen fwdCamera - ): - if bus not in valid_buses: - continue - - # When querying functional addresses, ideally we respond to everything that sends a first frame to avoid leaving the - # ECU in a temporary bad state. Note that we may not cover all ECUs and response offsets. TODO: query physical addrs - tx_addrs = vin_addrs - if functional_addrs is not None: - tx_addrs = [a for a in range(0x700, 0x800) if a != 0x7DF] + list(range(0x18DA00F1, 0x18DB00F1, 0x100)) - - try: - query = IsoTpParallelQuery(can_send, can_recv, bus, tx_addrs, [request, ], [response, ], response_offset=rx_offset, - functional_addrs=functional_addrs, debug=debug) - results = query.get_data(timeout) - - for addr in vin_addrs: - vin = results.get((addr, None)) - if vin is not None: - # Ford and Nissan pads with null bytes - if len(vin) in (19, 24): - vin = re.sub(b'\x00*$', b'', vin) - - # Honda Bosch response starts with a length, trim to correct length - if vin.startswith(b'\x11'): - vin = vin[1:18] - - carlog.error(f"got vin with {request=}") - return get_rx_addr_for_tx_addr(addr, rx_offset=rx_offset), bus, vin.decode() - except Exception: - carlog.exception("VIN query exception") - - carlog.error(f"vin query retry ({i+1}) ...") - - return -1, -1, VIN_UNKNOWN - - -if __name__ == "__main__": - import argparse - import time - import cereal.messaging as messaging - - parser = argparse.ArgumentParser(description='Get VIN of the car') - parser.add_argument('--debug', action='store_true') - parser.add_argument('--bus', type=int, default=1) - parser.add_argument('--timeout', type=float, default=0.1) - parser.add_argument('--retry', type=int, default=5) - args = parser.parse_args() - - sendcan = messaging.pub_sock('sendcan') - logcan = messaging.sub_sock('can') - time.sleep(1) - - vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (args.bus,), args.timeout, args.retry, debug=args.debug) - print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') diff --git a/selfdrive/car/volkswagen/__init__.py b/selfdrive/car/volkswagen/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py deleted file mode 100644 index 4f8552b16adbc5..00000000000000 --- a/selfdrive/car/volkswagen/carcontroller.py +++ /dev/null @@ -1,119 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import DT_CTRL, apply_driver_steer_torque_limits -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.helpers import clip -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.volkswagen import mqbcan, pqcan -from openpilot.selfdrive.car.volkswagen.values import CANBUS, CarControllerParams, VolkswagenFlags - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP): - super().__init__(dbc_name, CP) - self.CCP = CarControllerParams(CP) - self.CCS = pqcan if CP.flags & VolkswagenFlags.PQ else mqbcan - self.packer_pt = CANPacker(dbc_name) - self.ext_bus = CANBUS.pt if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera else CANBUS.cam - - self.apply_steer_last = 0 - self.gra_acc_counter_last = None - self.eps_timer_soft_disable_alert = False - self.hca_frame_timer_running = 0 - self.hca_frame_same_torque = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - can_sends = [] - - # **** Steering Controls ************************************************ # - - if self.frame % self.CCP.STEER_STEP == 0: - # Logic to avoid HCA state 4 "refused": - # * Don't steer unless HCA is in state 3 "ready" or 5 "active" - # * Don't steer at standstill - # * Don't send > 3.00 Newton-meters torque - # * Don't send the same torque for > 6 seconds - # * Don't send uninterrupted steering for > 360 seconds - # MQB racks reset the uninterrupted steering timer after a single frame - # of HCA disabled; this is done whenever output happens to be zero. - - if CC.latActive: - new_steer = int(round(actuators.steer * self.CCP.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) - self.hca_frame_timer_running += self.CCP.STEER_STEP - if self.apply_steer_last == apply_steer: - self.hca_frame_same_torque += self.CCP.STEER_STEP - if self.hca_frame_same_torque > self.CCP.STEER_TIME_STUCK_TORQUE / DT_CTRL: - apply_steer -= (1, -1)[apply_steer < 0] - self.hca_frame_same_torque = 0 - else: - self.hca_frame_same_torque = 0 - hca_enabled = abs(apply_steer) > 0 - else: - hca_enabled = False - apply_steer = 0 - - if not hca_enabled: - self.hca_frame_timer_running = 0 - - self.eps_timer_soft_disable_alert = self.hca_frame_timer_running > self.CCP.STEER_TIME_ALERT / DT_CTRL - self.apply_steer_last = apply_steer - can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hca_enabled)) - - if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - # Pacify VW Emergency Assist driver inactivity detection by changing its view of driver steering input torque - # to the greatest of actual driver input or 2x openpilot's output (1x openpilot output is not enough to - # consistently reset inactivity detection on straight level roads). See commaai/openpilot#23274 for background. - ea_simulated_torque = clip(apply_steer * 2, -self.CCP.STEER_MAX, self.CCP.STEER_MAX) - if abs(CS.out.steeringTorque) > abs(ea_simulated_torque): - ea_simulated_torque = CS.out.steeringTorque - can_sends.append(self.CCS.create_eps_update(self.packer_pt, CANBUS.cam, CS.eps_stock_values, ea_simulated_torque)) - - # **** Acceleration Controls ******************************************** # - - if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: - acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) - accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 - stopping = actuators.longControlState == LongCtrlState.stopping - starting = actuators.longControlState == LongCtrlState.pid and (CS.esp_hold_confirmation or CS.out.vEgo < self.CP.vEgoStopping) - can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, - acc_control, stopping, starting, CS.esp_hold_confirmation)) - - # **** HUD Controls ***************************************************** # - - if self.frame % self.CCP.LDW_STEP == 0: - hud_alert = 0 - if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): - hud_alert = self.CCP.LDW_MESSAGES["laneAssistTakeOver"] - can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.latActive, - CS.out.steeringPressed, hud_alert, hud_control)) - - if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: - lead_distance = 0 - if hud_control.leadVisible and self.frame * DT_CTRL > 1.0: # Don't display lead until we know the scaling factor - lead_distance = 512 if CS.upscale_lead_car_signal else 8 - acc_hud_status = self.CCS.acc_hud_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) - # FIXME: follow the recent displayed-speed updates, also use mph_kmh toggle to fix display rounding problem? - set_speed = hud_control.setSpeed * CV.MS_TO_KPH - can_sends.append(self.CCS.create_acc_hud_control(self.packer_pt, CANBUS.pt, acc_hud_status, set_speed, - lead_distance, hud_control.leadDistanceBars)) - - # **** Stock ACC Button Controls **************************************** # - - gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last - if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume): - can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, self.ext_bus, CS.gra_stock_values, - cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"] - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py deleted file mode 100644 index c53639a7dd701b..00000000000000 --- a/selfdrive/car/volkswagen/carstate.py +++ /dev/null @@ -1,398 +0,0 @@ -import numpy as np -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.volkswagen.values import DBC, CANBUS, NetworkLocation, TransmissionType, GearShifter, \ - CarControllerParams, VolkswagenFlags - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.frame = 0 - self.eps_init_complete = False - self.CCP = CarControllerParams(CP) - self.button_states = {button.event_type: False for button in self.CCP.BUTTONS} - self.esp_hold_confirmation = False - self.upscale_lead_car_signal = False - self.eps_stock_values = False - - def create_button_events(self, pt_cp, buttons): - button_events = [] - - for button in buttons: - state = pt_cp.vl[button.can_addr][button.can_msg] in button.values - if self.button_states[button.event_type] != state: - event = car.CarState.ButtonEvent.new_message() - event.type = button.event_type - event.pressed = state - button_events.append(event) - self.button_states[button.event_type] = state - - return button_events - - def update(self, pt_cp, cam_cp, ext_cp, trans_type): - if self.CP.flags & VolkswagenFlags.PQ: - return self.update_pq(pt_cp, cam_cp, ext_cp, trans_type) - - ret = car.CarState.new_message() - # Update vehicle speed and acceleration from ABS wheel speeds. - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["ESP_19"]["ESP_VL_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_VR_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_HL_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"], - ) - - ret.vEgoRaw = float(np.mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr])) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. - ret.steeringAngleDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradwinkel"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradwinkel"])] - ret.steeringRateDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradw_Geschw"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradw_Geschw"])] - ret.steeringTorque = pt_cp.vl["LH_EPS_03"]["EPS_Lenkmoment"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_Lenkmoment"])] - ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["ESP_02"]["ESP_Gierrate"] * (1, -1)[int(pt_cp.vl["ESP_02"]["ESP_VZ_Gierrate"])] * CV.DEG_TO_RAD - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) - ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) - - # VW Emergency Assist status tracking and mitigation - self.eps_stock_values = pt_cp.vl["LH_EPS_03"] - if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - ret.carFaultedNonCritical = bool(cam_cp.vl["HCA_01"]["EA_Ruckfreigabe"]) or cam_cp.vl["HCA_01"]["EA_ACC_Sollstatus"] > 0 - - # Update gas, brakes, and gearshift. - ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 - ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects - brake_pedal_pressed = bool(pt_cp.vl["Motor_14"]["MO_Fahrer_bremst"]) - brake_pressure_detected = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) - ret.brakePressed = brake_pedal_pressed or brake_pressure_detected - ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well - - # Update gear and/or clutch position data. - if trans_type == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_11"]["GE_Fahrstufe"], None)) - elif trans_type == TransmissionType.direct: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["EV_Gearshift"]["GearPosition"], None)) - elif trans_type == TransmissionType.manual: - ret.clutchPressed = not pt_cp.vl["Motor_14"]["MO_Kuppl_schalter"] - if bool(pt_cp.vl["Gateway_72"]["BCM1_Rueckfahrlicht_Schalter"]): - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # Update door and trunk/hatch lid open status. - ret.doorOpen = any([pt_cp.vl["Gateway_72"]["ZV_FT_offen"], - pt_cp.vl["Gateway_72"]["ZV_BT_offen"], - pt_cp.vl["Gateway_72"]["ZV_HFS_offen"], - pt_cp.vl["Gateway_72"]["ZV_HBFS_offen"], - pt_cp.vl["Gateway_72"]["ZV_HD_offen"]]) - - # Update seatbelt fastened status. - ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3 - - # Consume blind-spot monitoring info/warning LED states, if available. - # Infostufe: BSM LED on, Warnung: BSM LED flashing - if self.CP.enableBsm: - ret.leftBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_li"]) - ret.rightBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_re"]) - - # Consume factory LDW data relevant for factory SWA (Lane Change Assist) - # and capture it for forwarding to the blind spot radar controller - self.ldw_stock_values = cam_cp.vl["LDW_02"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} - - # Stock FCW is considered active if the release bit for brake-jerk warning - # is set. Stock AEB considered active if the partial braking or target - # braking release bits are set. - # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance - # Systems, chapter on Front Assist with Braking: Golf Family for all MQB - ret.stockFcw = bool(ext_cp.vl["ACC_10"]["AWV2_Freigabe"]) - ret.stockAeb = bool(ext_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(ext_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"]) - - # Update ACC radar status. - self.acc_type = ext_cp.vl["ACC_06"]["ACC_Typ"] - - # ACC okay but disabled (1), ACC ready (2), a radar visibility or other fault/disruption (6 or 7) - # currently regulating speed (3), driver accel override (4), brake only (5) - ret.cruiseState.available = pt_cp.vl["TSK_06"]["TSK_Status"] in (2, 3, 4, 5) - ret.cruiseState.enabled = pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5) - - if self.CP.pcmCruise: - # Cruise Control mode; check for distance UI setting from the radar. - # ECM does not manage this, so do not need to check for openpilot longitudinal - ret.cruiseState.nonAdaptive = ext_cp.vl["ACC_02"]["ACC_Gesetzte_Zeitluecke"] == 0 - else: - # Speed limiter mode; ECM faults if we command ACC while not pcmCruise - ret.cruiseState.nonAdaptive = bool(pt_cp.vl["TSK_06"]["TSK_Limiter_ausgewaehlt"]) - - ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) - - self.esp_hold_confirmation = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) - ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation - - # Update ACC setpoint. When the setpoint is zero or there's an error, the - # radar sends a set-speed of ~90.69 m/s / 203mph. - if self.CP.pcmCruise: - ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw_02"] * CV.KPH_TO_MS - if ret.cruiseState.speed > 90: - ret.cruiseState.speed = 0 - - # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough - ret.leftBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Left"]) - ret.rightBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Right"]) - ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) - self.gra_stock_values = pt_cp.vl["GRA_ACC_01"] - - # Additional safety checks performed in CarInterface. - ret.espDisabled = pt_cp.vl["ESP_21"]["ESP_Tastung_passiv"] != 0 - - # Digital instrument clusters expect the ACC HUD lead car distance to be scaled differently - self.upscale_lead_car_signal = bool(pt_cp.vl["Kombi_03"]["KBI_Variante"]) - - self.frame += 1 - return ret - - def update_pq(self, pt_cp, cam_cp, ext_cp, trans_type): - ret = car.CarState.new_message() - # Update vehicle speed and acceleration from ABS wheel speeds. - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["Bremse_3"]["Radgeschw__VL_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__VR_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__HL_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__HR_4_1"], - ) - - # vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF - ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. - ret.steeringAngleDeg = pt_cp.vl["Lenkhilfe_3"]["LH3_BLW"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_BLWSign"])] - ret.steeringRateDeg = pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit"] * (1, -1)[int(pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit_S"])] - ret.steeringTorque = pt_cp.vl["Lenkhilfe_3"]["LH3_LM"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_LMSign"])] - ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["Bremse_5"]["Giergeschwindigkeit"] * (1, -1)[int(pt_cp.vl["Bremse_5"]["Vorzeichen_der_Giergeschwindigk"])] * CV.DEG_TO_RAD - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["Lenkhilfe_2"]["LH2_Sta_HCA"]) - ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) - - # Update gas, brakes, and gearshift. - ret.gas = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] / 100.0 - ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["Bremse_5"]["Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects - ret.brakePressed = bool(pt_cp.vl["Motor_2"]["Bremslichtschalter"]) - ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) - - # Update gear and/or clutch position data. - if trans_type == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) - elif trans_type == TransmissionType.manual: - ret.clutchPressed = not pt_cp.vl["Motor_1"]["Kupplungsschalter"] - reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) - if reverse_light: - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # Update door and trunk/hatch lid open status. - ret.doorOpen = any([pt_cp.vl["Gate_Komf_1"]["GK1_Fa_Tuerkont"], - pt_cp.vl["Gate_Komf_1"]["BSK_BT_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HL_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HR_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HD_Hauptraste"]]) - - # Update seatbelt fastened status. - ret.seatbeltUnlatched = not bool(pt_cp.vl["Airbag_1"]["Gurtschalter_Fahrer"]) - - # Consume blind-spot monitoring info/warning LED states, if available. - # Infostufe: BSM LED on, Warnung: BSM LED flashing - if self.CP.enableBsm: - ret.leftBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_li"]) - ret.rightBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_re"]) - - # Consume factory LDW data relevant for factory SWA (Lane Change Assist) - # and capture it for forwarding to the blind spot radar controller - self.ldw_stock_values = cam_cp.vl["LDW_Status"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} - - # Stock FCW is considered active if the release bit for brake-jerk warning - # is set. Stock AEB considered active if the partial braking or target - # braking release bits are set. - # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance - # Systems, chapters on Front Assist with Braking and City Emergency - # Braking for the 2016 Passat NMS - # TODO: deferred until we can collect data on pre-MY2016 behavior, AWV message may be shorter with fewer signals - ret.stockFcw = False - ret.stockAeb = False - - # Update ACC radar status. - self.acc_type = ext_cp.vl["ACC_System"]["ACS_Typ_ACC"] - ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) - ret.cruiseState.enabled = pt_cp.vl["Motor_2"]["GRA_Status"] in (1, 2) - if self.CP.pcmCruise: - ret.accFaulted = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_StaACC"] in (6, 7) - else: - ret.accFaulted = pt_cp.vl["Motor_2"]["GRA_Status"] == 3 - - # Update ACC setpoint. When the setpoint reads as 255, the driver has not - # yet established an ACC setpoint, so treat it as zero. - ret.cruiseState.speed = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_V_Wunsch"] * CV.KPH_TO_MS - if ret.cruiseState.speed > 70: # 255 kph in m/s == no current setpoint - ret.cruiseState.speed = 0 - - # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_li"], - pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_re"]) - ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) - self.gra_stock_values = pt_cp.vl["GRA_Neu"] - - # Additional safety checks performed in CarInterface. - ret.espDisabled = bool(pt_cp.vl["Bremse_1"]["ESP_Passiv_getastet"]) - - self.frame += 1 - return ret - - def update_hca_state(self, hca_status): - # Treat INITIALIZING and FAULT as temporary for worst likely EPS recovery time, for cars without factory Lane Assist - # DISABLED means the EPS hasn't been configured to support Lane Assist - self.eps_init_complete = self.eps_init_complete or (hca_status in ("DISABLED", "READY", "ACTIVE") or self.frame > 600) - perm_fault = hca_status == "DISABLED" or (self.eps_init_complete and hca_status in ("INITIALIZING", "FAULT")) - temp_fault = hca_status in ("REJECTED", "PREEMPTED") or not self.eps_init_complete - return temp_fault, perm_fault - - @staticmethod - def get_can_parser(CP): - if CP.flags & VolkswagenFlags.PQ: - return CarState.get_can_parser_pq(CP) - - messages = [ - # sig_address, frequency - ("LWI_01", 100), # From J500 Steering Assist with integrated sensors - ("LH_EPS_03", 100), # From J500 Steering Assist with integrated sensors - ("ESP_19", 100), # From J104 ABS/ESP controller - ("ESP_05", 50), # From J104 ABS/ESP controller - ("ESP_21", 50), # From J104 ABS/ESP controller - ("Motor_20", 50), # From J623 Engine control module - ("TSK_06", 50), # From J623 Engine control module - ("ESP_02", 50), # From J104 ABS/ESP controller - ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls) - ("Gateway_72", 10), # From J533 CAN gateway (aggregated data) - ("Motor_14", 10), # From J623 Engine control module - ("Airbag_02", 5), # From J234 Airbag control module - ("Kombi_01", 2), # From J285 Instrument cluster - ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) - ("Kombi_03", 0), # From J285 instrument cluster (not present on older cars, 1Hz when present) - ] - - if CP.transmissionType == TransmissionType.automatic: - messages.append(("Getriebe_11", 20)) # From J743 Auto transmission control module - elif CP.transmissionType == TransmissionType.direct: - messages.append(("EV_Gearshift", 10)) # From J??? unknown EV control module - - if CP.networkLocation == NetworkLocation.fwdCamera: - # Radars are here on CANBUS.pt - messages += MqbExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += MqbExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) - - @staticmethod - def get_cam_can_parser(CP): - if CP.flags & VolkswagenFlags.PQ: - return CarState.get_cam_can_parser_pq(CP) - - messages = [] - - if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - messages += [ - ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not - ] - - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - # sig_address, frequency - ("LDW_02", 10) # From R242 Driver assistance camera - ] - else: - # Radars are here on CANBUS.cam - messages += MqbExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += MqbExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) - - @staticmethod - def get_can_parser_pq(CP): - messages = [ - # sig_address, frequency - ("Bremse_1", 100), # From J104 ABS/ESP controller - ("Bremse_3", 100), # From J104 ABS/ESP controller - ("Lenkhilfe_3", 100), # From J500 Steering Assist with integrated sensors - ("Lenkwinkel_1", 100), # From J500 Steering Assist with integrated sensors - ("Motor_3", 100), # From J623 Engine control module - ("Airbag_1", 50), # From J234 Airbag control module - ("Bremse_5", 50), # From J104 ABS/ESP controller - ("GRA_Neu", 50), # From J??? steering wheel control buttons - ("Kombi_1", 50), # From J285 Instrument cluster - ("Motor_2", 50), # From J623 Engine control module - ("Motor_5", 50), # From J623 Engine control module - ("Lenkhilfe_2", 20), # From J500 Steering Assist with integrated sensors - ("Gate_Komf_1", 10), # From J533 CAN gateway - ] - - if CP.transmissionType == TransmissionType.automatic: - messages += [("Getriebe_1", 100)] # From J743 Auto transmission control module - elif CP.transmissionType == TransmissionType.manual: - messages += [("Motor_1", 100)] # From J623 Engine control module - - if CP.networkLocation == NetworkLocation.fwdCamera: - # Extended CAN devices other than the camera are here on CANBUS.pt - messages += PqExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += PqExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) - - @staticmethod - def get_cam_can_parser_pq(CP): - - messages = [] - - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - # sig_address, frequency - ("LDW_Status", 10) # From R242 Driver assistance camera - ] - - if CP.networkLocation == NetworkLocation.gateway: - # Radars are here on CANBUS.cam - messages += PqExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += PqExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) - - -class MqbExtraSignals: - # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_messages = [ - ("ACC_06", 50), # From J428 ACC radar control module - ("ACC_10", 50), # From J428 ACC radar control module - ("ACC_02", 17), # From J428 ACC radar control module - ] - bsm_radar_messages = [ - ("SWA_01", 20), # From J1086 Lane Change Assist - ] - -class PqExtraSignals: - # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_messages = [ - ("ACC_System", 50), # From J428 ACC radar control module - ("ACC_GRA_Anzeige", 25), # From J428 ACC radar control module - ] - bsm_radar_messages = [ - ("SWA_1", 20), # From J1086 Lane Change Assist - ] diff --git a/selfdrive/car/volkswagen/fingerprints.py b/selfdrive/car/volkswagen/fingerprints.py deleted file mode 100644 index 71bdb2cfd4eaad..00000000000000 --- a/selfdrive/car/volkswagen/fingerprints.py +++ /dev/null @@ -1,1208 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.volkswagen.values import CAR - -Ecu = car.CarParams.Ecu - -# TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting - - -FW_VERSIONS = { - CAR.VOLKSWAGEN_ARTEON_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x873G0906259AH\xf1\x890001', - b'\xf1\x873G0906259F \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890005', - b'\xf1\x873G0906259M \xf1\x890003', - b'\xf1\x873G0906259N \xf1\x890004', - b'\xf1\x873G0906259P \xf1\x890001', - b'\xf1\x875NA907115H \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158L \xf1\x893611', - b'\xf1\x870DL300014C \xf1\x893704', - b'\xf1\x870GC300011L \xf1\x891401', - b'\xf1\x870GC300014M \xf1\x892802', - b'\xf1\x870GC300019G \xf1\x892804', - b'\xf1\x870GC300040P \xf1\x891401', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', - b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', - b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', - b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_ATLAS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703H906026AA\xf1\x899970', - b'\xf1\x8703H906026AG\xf1\x899973', - b'\xf1\x8703H906026AJ\xf1\x890638', - b'\xf1\x8703H906026AJ\xf1\x891017', - b'\xf1\x8703H906026AT\xf1\x891922', - b'\xf1\x8703H906026BC\xf1\x892664', - b'\xf1\x8703H906026F \xf1\x896696', - b'\xf1\x8703H906026F \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x896026', - b'\xf1\x8703H906026J \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x899971', - b'\xf1\x8703H906026S \xf1\x896693', - b'\xf1\x8703H906026S \xf1\x899970', - b'\xf1\x873CN906259 \xf1\x890005', - b'\xf1\x873CN906259F \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158A \xf1\x893387', - b'\xf1\x8709G927158DR\xf1\x893536', - b'\xf1\x8709G927158DR\xf1\x893742', - b'\xf1\x8709G927158EN\xf1\x893691', - b'\xf1\x8709G927158F \xf1\x893489', - b'\xf1\x8709G927158FT\xf1\x893835', - b'\xf1\x8709G927158GL\xf1\x893939', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\x0e1914151912001103111122031200', - b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\x0e2214152212001105141122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e2214152212001105141122052900', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105111122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B60924A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6N920A1', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_CADDY_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027T \xf1\x892363', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872K5959655E \xf1\x890018\xf1\x82\x05000P037605', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0155', - ], - }, - CAR.VOLKSWAGEN_CRAFTER_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056BP\xf1\x894729', - b'\xf1\x8704L906056EK\xf1\x896391', - b'\xf1\x8705L906023BC\xf1\x892688', - b'\xf1\x8705L906023MH\xf1\x892588', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', - b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', - b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', - b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', - b'\xf1\x872N0909143H \xf1\x897045\xf1\x82\x05263AZ309A2', - b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.VOLKSWAGEN_GOLF_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906016A \xf1\x897697', - b'\xf1\x8704E906016AD\xf1\x895758', - b'\xf1\x8704E906016CE\xf1\x899096', - b'\xf1\x8704E906016CH\xf1\x899226', - b'\xf1\x8704E906016N \xf1\x899105', - b'\xf1\x8704E906023AG\xf1\x891726', - b'\xf1\x8704E906023BN\xf1\x894518', - b'\xf1\x8704E906024K \xf1\x896811', - b'\xf1\x8704E906024K \xf1\x899970', - b'\xf1\x8704E906027GR\xf1\x892394', - b'\xf1\x8704E906027HD\xf1\x892603', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MA\xf1\x894958', - b'\xf1\x8704L906021DT\xf1\x895520', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021N \xf1\x895518', - b'\xf1\x8704L906021N \xf1\x898138', - b'\xf1\x8704L906026BN\xf1\x891197', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026NF\xf1\x899528', - b'\xf1\x8704L906056CL\xf1\x893823', - b'\xf1\x8704L906056CR\xf1\x895813', - b'\xf1\x8704L906056HE\xf1\x893758', - b'\xf1\x8704L906056HN\xf1\x896590', - b'\xf1\x8704L906056HT\xf1\x896591', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x870EA906016A \xf1\x898343', - b'\xf1\x870EA906016E \xf1\x894219', - b'\xf1\x870EA906016F \xf1\x894238', - b'\xf1\x870EA906016F \xf1\x895002', - b'\xf1\x870EA906016Q \xf1\x895993', - b'\xf1\x870EA906016S \xf1\x897207', - b'\xf1\x875G0906259 \xf1\x890007', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259J \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259N \xf1\x890003', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x892313', - b'\xf1\x875G0906259T \xf1\x890003', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890003', - b'\xf1\x878V0906259J \xf1\x890103', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906259K \xf1\x890003', - b'\xf1\x878V0906259P \xf1\x890001', - b'\xf1\x878V0906259Q \xf1\x890002', - b'\xf1\x878V0906259R \xf1\x890002', - b'\xf1\x878V0906264F \xf1\x890003', - b'\xf1\x878V0906264L \xf1\x890002', - b'\xf1\x878V0906264M \xf1\x890001', - b'\xf1\x878V09C0BB01 \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927749AP\xf1\x892943', - b'\xf1\x8709S927158A \xf1\x893585', - b'\xf1\x870CW300040H \xf1\x890606', - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041H \xf1\x891010', - b'\xf1\x870CW300042F \xf1\x891604', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043E \xf1\x891603', - b'\xf1\x870CW300044S \xf1\x894530', - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300045 \xf1\x894531', - b'\xf1\x870CW300047D \xf1\x895261', - b'\xf1\x870CW300047E \xf1\x895261', - b'\xf1\x870CW300048J \xf1\x890611', - b'\xf1\x870CW300049H \xf1\x890905', - b'\xf1\x870CW300050G \xf1\x891905', - b'\xf1\x870D9300012 \xf1\x894904', - b'\xf1\x870D9300012 \xf1\x894913', - b'\xf1\x870D9300012 \xf1\x894937', - b'\xf1\x870D9300012 \xf1\x895045', - b'\xf1\x870D9300012 \xf1\x895046', - b'\xf1\x870D9300014M \xf1\x895004', - b'\xf1\x870D9300014Q \xf1\x895006', - b'\xf1\x870D9300018 \xf1\x895201', - b'\xf1\x870D9300020J \xf1\x894902', - b'\xf1\x870D9300020Q \xf1\x895201', - b'\xf1\x870D9300020S \xf1\x895201', - b'\xf1\x870D9300040A \xf1\x893613', - b'\xf1\x870D9300040S \xf1\x894311', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300041P \xf1\x894507', - b'\xf1\x870DD300045K \xf1\x891120', - b'\xf1\x870DD300046F \xf1\x891601', - b'\xf1\x870GC300012A \xf1\x891401', - b'\xf1\x870GC300012A \xf1\x891403', - b'\xf1\x870GC300012A \xf1\x891422', - b'\xf1\x870GC300012M \xf1\x892301', - b'\xf1\x870GC300014B \xf1\x892401', - b'\xf1\x870GC300014B \xf1\x892403', - b'\xf1\x870GC300014B \xf1\x892405', - b'\xf1\x870GC300020G \xf1\x892401', - b'\xf1\x870GC300020G \xf1\x892403', - b'\xf1\x870GC300020G \xf1\x892404', - b'\xf1\x870GC300020N \xf1\x892804', - b'\xf1\x870GC300043T \xf1\x899999', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x13141600111233003142115A2232229333463100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', - b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', - b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', - b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', - b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', - b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', - b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00642A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', - b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', - b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', - b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890653', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_JETTA_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906024AK\xf1\x899937', - b'\xf1\x8704E906024AS\xf1\x899912', - b'\xf1\x8704E906024B \xf1\x895594', - b'\xf1\x8704E906024BC\xf1\x899971', - b'\xf1\x8704E906024BG\xf1\x891057', - b'\xf1\x8704E906024C \xf1\x899970', - b'\xf1\x8704E906024C \xf1\x899971', - b'\xf1\x8704E906024L \xf1\x895595', - b'\xf1\x8704E906024L \xf1\x899970', - b'\xf1\x8704E906027MS\xf1\x896223', - b'\xf1\x8705E906013DB\xf1\x893361', - b'\xf1\x875G0906259T \xf1\x890003', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158BQ\xf1\x893545', - b'\xf1\x8709S927158BS\xf1\x893642', - b'\xf1\x8709S927158BS\xf1\x893694', - b'\xf1\x8709S927158CK\xf1\x893770', - b'\xf1\x8709S927158JC\xf1\x894113', - b'\xf1\x8709S927158R \xf1\x893552', - b'\xf1\x8709S927158R \xf1\x893587', - b'\xf1\x870GC300020N \xf1\x892803', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314642011650169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314643011650169333463100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1311170031313300314240011150119333433100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1319170031313300314240011550159333463100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314642021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314643021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1317171231313500314642023050309333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A10A11A1', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x000_A1080_OM', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A10A01A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A10A01A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A10A11A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x875Q0907572N \xf1\x890681', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_PASSAT_MK8: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026E \xf1\x892114', - b'\xf1\x8704E906023AH\xf1\x893379', - b'\xf1\x8704E906023BM\xf1\x894522', - b'\xf1\x8704L906026DP\xf1\x891538', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x892012', - b'\xf1\x8704L906026GA\xf1\x892013', - b'\xf1\x8704L906026GK\xf1\x899971', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8705L906022A \xf1\x890827', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906264 \xf1\x890004', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041E \xf1\x891006', - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300042H \xf1\x891607', - b'\xf1\x870CW300043H \xf1\x891601', - b'\xf1\x870CW300048R \xf1\x890610', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014L \xf1\x895002', - b'\xf1\x870D9300018C \xf1\x895297', - b'\xf1\x870D9300041A \xf1\x894801', - b'\xf1\x870D9300042H \xf1\x894901', - b'\xf1\x870DD300045T \xf1\x891601', - b'\xf1\x870DD300046H \xf1\x891601', - b'\xf1\x870DL300011H \xf1\x895201', - b'\xf1\x870GC300042H \xf1\x891404', - b'\xf1\x870GC300043 \xf1\x892301', - b'\xf1\x870GC300046P \xf1\x892805', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', - b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001344701311442900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011111200631145171716121691132111', - b'\xf1\x875QF959655S \xf1\x890639\xf1\x82\x13131100131300111111000120----2211114A48', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521B00606A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516B00501A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00603A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00703A1', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572A \xf1\x890126', - b'\xf1\x873Q0907572A \xf1\x890130', - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x873Q0907572C \xf1\x890196', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_PASSAT_NMS: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8706K906016C \xf1\x899609', - b'\xf1\x8706K906016E \xf1\x899830', - b'\xf1\x8706K906016G \xf1\x891124', - b'\xf1\x8706K906071BJ\xf1\x894891', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158AB\xf1\x893318', - b'\xf1\x8709G927158BD\xf1\x893121', - b'\xf1\x8709G927158DK\xf1\x893594', - b'\xf1\x8709G927158FQ\xf1\x893745', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x87561959655 \xf1\x890210\xf1\x82\x1212121111113000102011--121012--101312', - b'\xf1\x87561959655C \xf1\x890508\xf1\x82\x1215141111121100314919--153015--304831', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x87561907567A \xf1\x890132', - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0152', - ], - }, - CAR.VOLKSWAGEN_POLO_MK6: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025H \xf1\x895177', - b'\xf1\x8705C906032J \xf1\x891702', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042D \xf1\x891612', - b'\xf1\x870CW300050D \xf1\x891908', - b'\xf1\x870CW300051G \xf1\x891909', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - b'\xf1\x872Q2909144AB\xf1\x896050', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.VOLKSWAGEN_SHARAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906016HE\xf1\x894635', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', - ], - }, - CAR.VOLKSWAGEN_TAOS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906025CK\xf1\x892228', - b'\xf1\x8704E906027NJ\xf1\x891445', - b'\xf1\x8704E906027NP\xf1\x891286', - b'\xf1\x8705E906013BD\xf1\x892496', - b'\xf1\x8705E906013E \xf1\x891624', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158EM\xf1\x893812', - b'\xf1\x8709S927158BL\xf1\x893791', - b'\xf1\x8709S927158CR\xf1\x893924', - b'\xf1\x8709S927158DN\xf1\x893946', - b'\xf1\x8709S927158FF\xf1\x893876', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', - b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TCROSS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300050E \xf1\x891903', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1212130411110411--04041104141311152H14', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TIGUAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026D \xf1\x893680', - b'\xf1\x8704E906024AP\xf1\x891461', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906026EJ\xf1\x893916', - b'\xf1\x8704L906027G \xf1\x899893', - b'\xf1\x8705E906018BS\xf1\x890914', - b'\xf1\x875N0906259 \xf1\x890002', - b'\xf1\x875NA906259H \xf1\x890002', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x875NA907115J \xf1\x890002', - b'\xf1\x875NA907115K \xf1\x890004', - b'\xf1\x8783A907115 \xf1\x890007', - b'\xf1\x8783A907115B \xf1\x890005', - b'\xf1\x8783A907115F \xf1\x890002', - b'\xf1\x8783A907115G \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890002', - b'\xf1\x8783A907115Q \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158DS\xf1\x893699', - b'\xf1\x8709G927158DT\xf1\x893698', - b'\xf1\x8709G927158FM\xf1\x893757', - b'\xf1\x8709G927158GC\xf1\x893821', - b'\xf1\x8709G927158GD\xf1\x893820', - b'\xf1\x8709G927158GM\xf1\x893936', - b'\xf1\x8709G927158GN\xf1\x893938', - b'\xf1\x8709G927158HB\xf1\x894069', - b'\xf1\x8709G927158HC\xf1\x894070', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DD300046K \xf1\x892302', - b'\xf1\x870DL300011N \xf1\x892001', - b'\xf1\x870DL300011N \xf1\x892012', - b'\xf1\x870DL300011N \xf1\x892014', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012P \xf1\x892103', - b'\xf1\x870DL300013A \xf1\x893005', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870DL300013G \xf1\x892120', - b'\xf1\x870DL300014C \xf1\x893703', - b'\xf1\x870GC300013P \xf1\x892401', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1316143231313500314617011730179333423100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1316143231313500314617011730179333423100', - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x1331310031333334313132573732379333313100', - b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1311140031333300314232583632369333423100', - b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1331310031333334313132013730379333423100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1316143231313500314641011750179333423100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1312110031333300314240013750379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1312110031333300314240583752379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333336313140013950399333423100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', - b'\xf1\x875Q0959655CD\xf1\x890421\xf1\x82\x13123112313333003145406F6154619333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6050705', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6070705', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6017A00', - b'\xf1\x875QF909144 \xf1\x895572\xf1\x82\x0571A60833A1', - b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A60634A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002RA60A2ROM', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60804A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60804A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TOURAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906025BE\xf1\x890720', - b'\xf1\x8704E906027HQ\xf1\x893746', - b'\xf1\x8704L906026HM\xf1\x893017', - b'\xf1\x8705E906018CQ\xf1\x890808', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020A \xf1\x891936', - b'\xf1\x870CW300041E \xf1\x891005', - b'\xf1\x870CW300041Q \xf1\x891606', - b'\xf1\x870CW300051M \xf1\x891926', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x1336350021353335314132014730479333313100', - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x13363500213533353141324C4732479333313100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', - b'\xf1\x875QD959655AJ\xf1\x890421\xf1\x82\x1336350021313300314240023330339333663100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', - b'\xf1\x875QD909144F \xf1\x891082\xf1\x82\x0521A00642A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_TRANSPORTER_T61: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056AG\xf1\x899970', - b'\xf1\x8704L906056AL\xf1\x899970', - b'\xf1\x8704L906057AP\xf1\x891186', - b'\xf1\x8704L906057N \xf1\x890413', - b'\xf1\x8705L906023E \xf1\x891352', - b'\xf1\x8705L906023MR\xf1\x892582', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870BT300012E \xf1\x893105', - b'\xf1\x870BT300012G \xf1\x893102', - b'\xf1\x870BT300046R \xf1\x893102', - b'\xf1\x870DV300012B \xf1\x893701', - b'\xf1\x870DV300012B \xf1\x893702', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', - b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', - b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', - b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.VOLKSWAGEN_TROC_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018AT\xf1\x899640', - b'\xf1\x8705E906018CK\xf1\x890863', - b'\xf1\x8705E906018P \xf1\x896020', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870CW300050J \xf1\x891911', - b'\xf1\x870CW300051M \xf1\x891925', - b'\xf1\x870CW300051M \xf1\x891928', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', - b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1154119333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', - b'\xf1\x875WA907144Q \xf1\x891063\xf1\x82\x001O06081OOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.AUDI_A3_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906023AN\xf1\x893695', - b'\xf1\x8704E906023AR\xf1\x893440', - b'\xf1\x8704E906023BL\xf1\x895190', - b'\xf1\x8704E906027CJ\xf1\x897798', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x875G0906259A \xf1\x890004', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x878V0906259E \xf1\x890001', - b'\xf1\x878V0906259F \xf1\x890002', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890002', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906264B \xf1\x890003', - b'\xf1\x878V0907115B \xf1\x890007', - b'\xf1\x878V0907404A \xf1\x890005', - b'\xf1\x878V0907404G \xf1\x890005', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300048 \xf1\x895201', - b'\xf1\x870D9300012 \xf1\x894912', - b'\xf1\x870D9300012 \xf1\x894931', - b'\xf1\x870D9300012K \xf1\x894513', - b'\xf1\x870D9300012L \xf1\x894521', - b'\xf1\x870D9300013B \xf1\x894902', - b'\xf1\x870D9300013B \xf1\x894931', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300043T \xf1\x899699', - b'\xf1\x870DD300046 \xf1\x891604', - b'\xf1\x870DD300046A \xf1\x891602', - b'\xf1\x870DD300046F \xf1\x891602', - b'\xf1\x870DD300046G \xf1\x891601', - b'\xf1\x870DL300012E \xf1\x892012', - b'\xf1\x870DL300012H \xf1\x892112', - b'\xf1\x870GC300011 \xf1\x890403', - b'\xf1\x870GC300013M \xf1\x892402', - b'\xf1\x870GC300042J \xf1\x891402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\x111111001111111206110412111321139114', - b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', - b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', - b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--171115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112110004110411111421149114', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112111104110411111521159114', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521G0G809A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00303A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00803A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521G00807A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', - b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572P \xf1\x890682', - ], - }, - CAR.AUDI_Q2_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027JT\xf1\x894145', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041F \xf1\x891006', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.AUDI_Q3_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018N \xf1\x899970', - b'\xf1\x8705L906022M \xf1\x890901', - b'\xf1\x8783A906259 \xf1\x890001', - b'\xf1\x8783A906259 \xf1\x890005', - b'\xf1\x8783A906259C \xf1\x890002', - b'\xf1\x8783A906259D \xf1\x890001', - b'\xf1\x8783A906259F \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158CN\xf1\x893608', - b'\xf1\x8709G927158FL\xf1\x893758', - b'\xf1\x8709G927158GG\xf1\x893825', - b'\xf1\x8709G927158GP\xf1\x893937', - b'\xf1\x870GC300045D \xf1\x892802', - b'\xf1\x870GC300046F \xf1\x892701', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218A219321532111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60733A1', - b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SEAT_ATECA_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027KA\xf1\x893749', - b'\xf1\x8704L906021EL\xf1\x897542', - b'\xf1\x8704L906026BP\xf1\x891198', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906056CR\xf1\x892181', - b'\xf1\x8704L906056CR\xf1\x892797', - b'\xf1\x8705E906018AS\xf1\x899596', - b'\xf1\x8781A906259B \xf1\x890003', - b'\xf1\x878V0906264H \xf1\x890005', - b'\xf1\x878V0907115E \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041G \xf1\x891003', - b'\xf1\x870CW300050J \xf1\x891908', - b'\xf1\x870D9300014S \xf1\x895202', - b'\xf1\x870D9300042M \xf1\x895016', - b'\xf1\x870GC300014P \xf1\x892801', - b'\xf1\x870GC300043A \xf1\x892304', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1212001211001305121211052900', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1113121149', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571N60511A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521N01342A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511N01805A0', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N05808A1', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x0013N619137N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_FABIA_MK4: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018CF\xf1\x891905', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300051M \xf1\x891936', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144S \xf1\x896042', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.SKODA_KAMIQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - b'\xf1\x8705C906032M \xf1\x891333', - b'\xf1\x8705C906032M \xf1\x892365', - b'\xf1\x8705E906013CK\xf1\x892540', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020 \xf1\x891906', - b'\xf1\x870CW300020 \xf1\x891907', - b'\xf1\x870CW300020T \xf1\x892204', - b'\xf1\x870CW300050 \xf1\x891709', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x12111104111104112104040404111111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x122221042111042121040404042E2711152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', - b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144AB\xf1\x896050', - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KAROQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906013CL\xf1\x892541', - b'\xf1\x8705E906013H \xf1\x892407', - b'\xf1\x8705E906018P \xf1\x895472', - b'\xf1\x8705E906018P \xf1\x896020', - b'\xf1\x8705L906022BS\xf1\x890913', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020T \xf1\x892202', - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870GC300014L \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1213001211001101131122012100', - b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KODIAQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027DD\xf1\x893123', - b'\xf1\x8704E906027LD\xf1\x893433', - b'\xf1\x8704E906027NB\xf1\x896517', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026DE\xf1\x895418', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906026HT\xf1\x893617', - b'\xf1\x8705E906018DJ\xf1\x890915', - b'\xf1\x8705E906018DJ\xf1\x891903', - b'\xf1\x8705L906022GM\xf1\x893411', - b'\xf1\x875NA906259E \xf1\x890003', - b'\xf1\x875NA907115D \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x8783A907115E \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870D9300014S \xf1\x895201', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DL300011N \xf1\x892014', - b'\xf1\x870DL300012G \xf1\x892006', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012N \xf1\x892110', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870GC300014N \xf1\x892801', - b'\xf1\x870GC300018S \xf1\x892803', - b'\xf1\x870GC300019H \xf1\x892806', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r11110011110011031111310311', - b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', - b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', - b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121246149', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x0025T6BA25OM', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_OCTAVIA_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025L \xf1\x896198', - b'\xf1\x8704E906016ER\xf1\x895823', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MH\xf1\x894786', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021ER\xf1\x898361', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026BS\xf1\x891541', - b'\xf1\x8704L906026BT\xf1\x897612', - b'\xf1\x875G0906259C \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041L \xf1\x891601', - b'\xf1\x870CW300041N \xf1\x891605', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043P \xf1\x891605', - b'\xf1\x870D9300012H \xf1\x894518', - b'\xf1\x870D9300014T \xf1\x895221', - b'\xf1\x870D9300041C \xf1\x894936', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041J \xf1\x894902', - b'\xf1\x870D9300041P \xf1\x894507', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655AK\xf1\x890306\xf1\x82\r31210031210021033733310331', - b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', - b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01513A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00603A1', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', - b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567P \xf1\x890100\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_SUPERB_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027BS\xf1\x892887', - b'\xf1\x8704E906027BT\xf1\x899042', - b'\xf1\x8704L906026ET\xf1\x891343', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x891196', - b'\xf1\x8704L906026KA\xf1\x896014', - b'\xf1\x8704L906026KB\xf1\x894071', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8704L906026MT\xf1\x893076', - b'\xf1\x8705L906022BK\xf1\x899971', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906259L \xf1\x890003', - b'\xf1\x873G0906264A \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300043B \xf1\x891603', - b'\xf1\x870CW300049Q \xf1\x890906', - b'\xf1\x870D9300011T \xf1\x894801', - b'\xf1\x870D9300012 \xf1\x894940', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014K \xf1\x895006', - b'\xf1\x870D9300041H \xf1\x894905', - b'\xf1\x870D9300042M \xf1\x895013', - b'\xf1\x870D9300043F \xf1\x895202', - b'\xf1\x870GC300013K \xf1\x892403', - b'\xf1\x870GC300014M \xf1\x892801', - b'\xf1\x870GC300019G \xf1\x892803', - b'\xf1\x870GC300043 \xf1\x892301', - b'\xf1\x870GC300046D \xf1\x892402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121118112231292221111', - b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', - b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1333310031313100313152015351539331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060700', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, -} diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py deleted file mode 100644 index 77e56875bf2490..00000000000000 --- a/selfdrive/car/volkswagen/interface.py +++ /dev/null @@ -1,131 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.volkswagen.values import CAR, CANBUS, CarControllerParams, NetworkLocation, TransmissionType, GearShifter, VolkswagenFlags - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName - - -class CarInterface(CarInterfaceBase): - def __init__(self, CP, CarController, CarState): - super().__init__(CP, CarController, CarState) - - if CP.networkLocation == NetworkLocation.fwdCamera: - self.ext_bus = CANBUS.pt - self.cp_ext = self.cp - else: - self.ext_bus = CANBUS.cam - self.cp_ext = self.cp_cam - - @staticmethod - def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): - ret.carName = "volkswagen" - ret.radarUnavailable = True - - if ret.flags & VolkswagenFlags.PQ: - # Set global PQ35/PQ46/NMS parameters - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagenPq)] - ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1 - - if 0x440 in fingerprint[0] or docs: # Getriebe_1 - ret.transmissionType = TransmissionType.automatic - else: - ret.transmissionType = TransmissionType.manual - - if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 - ret.networkLocation = NetworkLocation.gateway - else: - ret.networkLocation = NetworkLocation.fwdCamera - - # The PQ port is in dashcam-only mode due to a fixed six-minute maximum timer on HCA steering. An unsupported - # EPS flash update to work around this timer, and enable steering down to zero, is available from: - # https://github.com/pd0wm/pq-flasher - # It is documented in a four-part blog series: - # https://blog.willemmelching.nl/carhacking/2022/01/02/vw-part1/ - # Panda ALLOW_DEBUG firmware required. - ret.dashcamOnly = True - - else: - # Set global MQB parameters - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)] - ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 - - if 0xAD in fingerprint[0] or docs: # Getriebe_11 - ret.transmissionType = TransmissionType.automatic - elif 0x187 in fingerprint[0]: # EV_Gearshift - ret.transmissionType = TransmissionType.direct - else: - ret.transmissionType = TransmissionType.manual - - if any(msg in fingerprint[1] for msg in (0x40, 0x86, 0xB2, 0xFD)): # Airbag_01, LWI_01, ESP_19, ESP_21 - ret.networkLocation = NetworkLocation.gateway - else: - ret.networkLocation = NetworkLocation.fwdCamera - - if 0x126 in fingerprint[2]: # HCA_01 - ret.flags |= VolkswagenFlags.STOCK_HCA_PRESENT.value - - # Global lateral tuning defaults, can be overridden per-vehicle - - ret.steerLimitTimer = 0.4 - if ret.flags & VolkswagenFlags.PQ: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - else: - ret.steerActuatorDelay = 0.1 - ret.lateralTuning.pid.kpBP = [0.] - ret.lateralTuning.pid.kiBP = [0.] - ret.lateralTuning.pid.kf = 0.00006 - ret.lateralTuning.pid.kpV = [0.6] - ret.lateralTuning.pid.kiV = [0.2] - - # Global longitudinal tuning defaults, can be overridden per-vehicle - - ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs - if experimental_long: - # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL - if ret.transmissionType == TransmissionType.manual: - ret.minEnableSpeed = 4.5 - - ret.pcmCruise = not ret.openpilotLongitudinalControl - ret.stoppingControl = True - ret.stopAccel = -0.55 - ret.vEgoStarting = 0.1 - ret.vEgoStopping = 0.5 - ret.autoResumeSng = ret.minEnableSpeed == -1 - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_ext, self.CP.transmissionType) - - events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], - pcm_enable=not self.CS.CP.openpilotLongitudinalControl, - enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) - - # Low speed steer alert hysteresis logic - if (self.CP.minSteerSpeed - 1e-3) > CarControllerParams.DEFAULT_MIN_STEER_SPEED and ret.vEgo < (self.CP.minSteerSpeed + 1.): - self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 2.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(EventName.belowSteerSpeed) - - if self.CS.CP.openpilotLongitudinalControl: - if ret.vEgo < self.CP.minEnableSpeed + 0.5: - events.add(EventName.belowEngageSpeed) - if c.enabled and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.speedTooLow) - - if self.CC.eps_timer_soft_disable_alert: - events.add(EventName.steerTimeLimit) - - ret.events = events.to_msg() - - return ret - diff --git a/selfdrive/car/volkswagen/mqbcan.py b/selfdrive/car/volkswagen/mqbcan.py deleted file mode 100644 index 763908b6b2730e..00000000000000 --- a/selfdrive/car/volkswagen/mqbcan.py +++ /dev/null @@ -1,137 +0,0 @@ -def create_steering_control(packer, bus, apply_steer, lkas_enabled): - values = { - "HCA_01_Status_HCA": 5 if lkas_enabled else 3, - "HCA_01_LM_Offset": abs(apply_steer), - "HCA_01_LM_OffSign": 1 if apply_steer < 0 else 0, - "HCA_01_Vib_Freq": 18, - "HCA_01_Sendestatus": 1 if lkas_enabled else 0, - "EA_ACC_Wunschgeschwindigkeit": 327.36, - } - return packer.make_can_msg("HCA_01", bus, values) - - -def create_eps_update(packer, bus, eps_stock_values, ea_simulated_torque): - values = {s: eps_stock_values[s] for s in [ - "COUNTER", # Sync counter value to EPS output - "EPS_Lenkungstyp", # EPS rack type - "EPS_Berechneter_LW", # Absolute raw steering angle - "EPS_VZ_BLW", # Raw steering angle sign - "EPS_HCA_Status", # EPS HCA control status - ]} - - values.update({ - # Absolute driver torque input and sign, with EA inactivity mitigation - "EPS_Lenkmoment": abs(ea_simulated_torque), - "EPS_VZ_Lenkmoment": 1 if ea_simulated_torque < 0 else 0, - }) - - return packer.make_can_msg("LH_EPS_03", bus, values) - - -def create_lka_hud_control(packer, bus, ldw_stock_values, lat_active, steering_pressed, hud_alert, hud_control): - values = {} - if len(ldw_stock_values): - values = {s: ldw_stock_values[s] for s in [ - "LDW_SW_Warnung_links", # Blind spot in warning mode on left side due to lane departure - "LDW_SW_Warnung_rechts", # Blind spot in warning mode on right side due to lane departure - "LDW_Seite_DLCTLC", # Direction of most likely lane departure (left or right) - "LDW_DLC", # Lane departure, distance to line crossing - "LDW_TLC", # Lane departure, time to line crossing - ]} - - values.update({ - "LDW_Status_LED_gelb": 1 if lat_active and steering_pressed else 0, - "LDW_Status_LED_gruen": 1 if lat_active and not steering_pressed else 0, - "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, - "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, - "LDW_Texte": hud_alert, - }) - return packer.make_can_msg("LDW_02", bus, values) - - -def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): - values = {s: gra_stock_values[s] for s in [ - "GRA_Hauptschalter", # ACC button, on/off - "GRA_Typ_Hauptschalter", # ACC main button type - "GRA_Codierung", # ACC button configuration/coding - "GRA_Tip_Stufe_2", # unknown related to stalk type - "GRA_ButtonTypeInfo", # unknown related to stalk type - ]} - - values.update({ - "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, - "GRA_Abbrechen": cancel, - "GRA_Tip_Wiederaufnahme": resume, - }) - - return packer.make_can_msg("GRA_ACC_01", bus, values) - - -def acc_control_value(main_switch_on, acc_faulted, long_active): - if acc_faulted: - acc_control = 6 - elif long_active: - acc_control = 3 - elif main_switch_on: - acc_control = 2 - else: - acc_control = 0 - - return acc_control - - -def acc_hud_status_value(main_switch_on, acc_faulted, long_active): - # TODO: happens to resemble the ACC control value for now, but extend this for init/gas override later - return acc_control_value(main_switch_on, acc_faulted, long_active) - - -def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): - commands = [] - - acc_06_values = { - "ACC_Typ": acc_type, - "ACC_Status_ACC": acc_control, - "ACC_StartStopp_Info": acc_enabled, - "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, - "ACC_zul_Regelabw_unten": 0.2, # TODO: dynamic adjustment of comfort-band - "ACC_zul_Regelabw_oben": 0.2, # TODO: dynamic adjustment of comfort-band - "ACC_neg_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits - "ACC_pos_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits - "ACC_Anfahren": starting, - "ACC_Anhalten": stopping, - } - commands.append(packer.make_can_msg("ACC_06", bus, acc_06_values)) - - if starting: - acc_hold_type = 4 # hold release / startup - elif esp_hold: - acc_hold_type = 3 # hold standby - elif stopping: - acc_hold_type = 1 # hold request - else: - acc_hold_type = 0 - - acc_07_values = { - "ACC_Anhalteweg": 0.3 if stopping else 20.46, # Distance to stop (stopping coordinator handles terminal roll-out) - "ACC_Freilauf_Info": 2 if acc_enabled else 0, - "ACC_Folgebeschl": 3.02, # Not using secondary controller accel unless and until we understand its impact - "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, - "ACC_Anforderung_HMS": acc_hold_type, - "ACC_Anfahren": starting, - "ACC_Anhalten": stopping, - } - commands.append(packer.make_can_msg("ACC_07", bus, acc_07_values)) - - return commands - - -def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): - values = { - "ACC_Status_Anzeige": acc_hud_status, - "ACC_Wunschgeschw_02": set_speed if set_speed < 250 else 327.36, - "ACC_Gesetzte_Zeitluecke": distance + 2, - "ACC_Display_Prio": 3, - "ACC_Abstandsindex": lead_distance, - } - - return packer.make_can_msg("ACC_02", bus, values) diff --git a/selfdrive/car/volkswagen/pqcan.py b/selfdrive/car/volkswagen/pqcan.py deleted file mode 100644 index f8d161b9701acc..00000000000000 --- a/selfdrive/car/volkswagen/pqcan.py +++ /dev/null @@ -1,105 +0,0 @@ -def create_steering_control(packer, bus, apply_steer, lkas_enabled): - values = { - "LM_Offset": abs(apply_steer), - "LM_OffSign": 1 if apply_steer < 0 else 0, - "HCA_Status": 5 if (lkas_enabled and apply_steer != 0) else 3, - "Vib_Freq": 16, - } - - return packer.make_can_msg("HCA_1", bus, values) - - -def create_lka_hud_control(packer, bus, ldw_stock_values, lat_active, steering_pressed, hud_alert, hud_control): - values = {} - if len(ldw_stock_values): - values = {s: ldw_stock_values[s] for s in [ - "LDW_SW_Warnung_links", # Blind spot in warning mode on left side due to lane departure - "LDW_SW_Warnung_rechts", # Blind spot in warning mode on right side due to lane departure - "LDW_Seite_DLCTLC", # Direction of most likely lane departure (left or right) - "LDW_DLC", # Lane departure, distance to line crossing - "LDW_TLC", # Lane departure, time to line crossing - ]} - - values.update({ - "LDW_Lampe_gelb": 1 if lat_active and steering_pressed else 0, - "LDW_Lampe_gruen": 1 if lat_active and not steering_pressed else 0, - "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, - "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, - "LDW_Textbits": hud_alert, - }) - - return packer.make_can_msg("LDW_Status", bus, values) - - -def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): - values = {s: gra_stock_values[s] for s in [ - "GRA_Hauptschalt", # ACC button, on/off - "GRA_Typ_Hauptschalt", # ACC button, momentary vs latching - "GRA_Kodierinfo", # ACC button, configuration - "GRA_Sender", # ACC button, CAN message originator - ]} - - values.update({ - "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, - "GRA_Abbrechen": cancel, - "GRA_Recall": resume, - }) - - return packer.make_can_msg("GRA_Neu", bus, values) - - -def acc_control_value(main_switch_on, acc_faulted, long_active): - if long_active: - acc_control = 1 - elif main_switch_on: - acc_control = 2 - else: - acc_control = 0 - - return acc_control - - -def acc_hud_status_value(main_switch_on, acc_faulted, long_active): - if acc_faulted: - hud_status = 6 - elif long_active: - hud_status = 3 - elif main_switch_on: - hud_status = 2 - else: - hud_status = 0 - - return hud_status - - -def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): - commands = [] - - values = { - "ACS_Sta_ADR": acc_control, - "ACS_StSt_Info": acc_enabled, - "ACS_Typ_ACC": acc_type, - "ACS_Anhaltewunsch": acc_type == 1 and stopping, - "ACS_FreigSollB": acc_enabled, - "ACS_Sollbeschl": accel if acc_enabled else 3.01, - "ACS_zul_Regelabw": 0.2 if acc_enabled else 1.27, - "ACS_max_AendGrad": 3.0 if acc_enabled else 5.08, - } - - commands.append(packer.make_can_msg("ACC_System", bus, values)) - - return commands - - -def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): - values = { - "ACA_StaACC": acc_hud_status, - "ACA_Zeitluecke": distance + 2, - "ACA_V_Wunsch": set_speed, - "ACA_gemZeitl": lead_distance, - "ACA_PrioDisp": 3, - # TODO: restore dynamic pop-to-foreground/highlight behavior with ACA_PrioDisp and ACA_AnzDisplay - # TODO: ACA_kmh_mph handling probably needed to resolve rounding errors in displayed setpoint - } - - return packer.make_can_msg("ACC_GRA_Anzeige", bus, values) diff --git a/selfdrive/car/volkswagen/radar_interface.py b/selfdrive/car/volkswagen/radar_interface.py deleted file mode 100644 index e654bd61fd4afd..00000000000000 --- a/selfdrive/car/volkswagen/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/volkswagen/tests/test_volkswagen.py b/selfdrive/car/volkswagen/tests/test_volkswagen.py deleted file mode 100644 index 00025781057324..00000000000000 --- a/selfdrive/car/volkswagen/tests/test_volkswagen.py +++ /dev/null @@ -1,60 +0,0 @@ -import random -import re - -from cereal import car -from openpilot.selfdrive.car.volkswagen.values import CAR, FW_QUERY_CONFIG, WMI -from openpilot.selfdrive.car.volkswagen.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - -CHASSIS_CODE_PATTERN = re.compile('[A-Z0-9]{2}') -# TODO: determine the unknown groups -SPARE_PART_FW_PATTERN = re.compile(b'\xf1\x87(?P[0-9][0-9A-Z]{2})(?P[0-9][0-9A-Z][0-9])(?P[0-9A-Z]{2}[0-9])([A-Z0-9]| )') - - -class TestVolkswagenPlatformConfigs: - def test_spare_part_fw_pattern(self, subtests): - # Relied on for determining if a FW is likely VW - for platform, ecus in FW_VERSIONS.items(): - with subtests.test(platform=platform.value): - for fws in ecus.values(): - for fw in fws: - assert SPARE_PART_FW_PATTERN.match(fw) is not None, f"Bad FW: {fw}" - - def test_chassis_codes(self, subtests): - for platform in CAR: - with subtests.test(platform=platform.value): - assert len(platform.config.wmis) > 0, "WMIs not set" - assert len(platform.config.chassis_codes) > 0, "Chassis codes not set" - assert all(CHASSIS_CODE_PATTERN.match(cc) for cc in \ - platform.config.chassis_codes), "Bad chassis codes" - - # No two platforms should share chassis codes - for comp in CAR: - if platform == comp: - continue - assert set() == platform.config.chassis_codes & comp.config.chassis_codes, \ - f"Shared chassis codes: {comp}" - - def test_custom_fuzzy_fingerprinting(self, subtests): - all_radar_fw = list({fw for ecus in FW_VERSIONS.values() for fw in ecus[Ecu.fwdRadar, 0x757, None]}) - - for platform in CAR: - with subtests.test(platform=platform.name): - for wmi in WMI: - for chassis_code in platform.config.chassis_codes | {"00"}: - vin = ["0"] * 17 - vin[0:3] = wmi - vin[6:8] = chassis_code - vin = "".join(vin) - - # Check a few FW cases - expected, unexpected - for radar_fw in random.sample(all_radar_fw, 5) + [b'\xf1\x875Q0907572G \xf1\x890571', b'\xf1\x877H9907572AA\xf1\x890396']: - should_match = ((wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes) and - radar_fw in all_radar_fw) - - live_fws = {(0x757, None): [radar_fw]} - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fws, vin, FW_VERSIONS) - - expected_matches = {platform} if should_match else set() - assert expected_matches == matches, "Bad match" diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py deleted file mode 100644 index 27816712f6da26..00000000000000 --- a/selfdrive/car/volkswagen/values.py +++ /dev/null @@ -1,516 +0,0 @@ -from collections import defaultdict, namedtuple -from dataclasses import dataclass, field -from enum import Enum, IntFlag, StrEnum - -from cereal import car -from panda.python import uds -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car import dbc_dict, CarSpecs, DbcDict, PlatformConfig, Platforms -from openpilot.selfdrive.car.conversions import Conversions as CV -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device -from openpilot.selfdrive.car.fw_query_definitions import EcuAddrSubAddr, FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu -NetworkLocation = car.CarParams.NetworkLocation -TransmissionType = car.CarParams.TransmissionType -GearShifter = car.CarState.GearShifter -Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) - - -class CarControllerParams: - STEER_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz - ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz - - # Documented lateral limits: 3.00 Nm max, rate of change 5.00 Nm/sec. - # MQB vs PQ maximums are shared, but rate-of-change limited differently - # based on safety requirements driven by lateral accel testing. - - STEER_MAX = 300 # Max heading control assist torque 3.00 Nm - STEER_DRIVER_MULTIPLIER = 3 # weight driver torque heavily - STEER_DRIVER_FACTOR = 1 # from dbc - - STEER_TIME_MAX = 360 # Max time that EPS allows uninterrupted HCA steering control - STEER_TIME_ALERT = STEER_TIME_MAX - 10 # If mitigation fails, time to soft disengage before EPS timer expires - STEER_TIME_STUCK_TORQUE = 1.9 # EPS limits same torque to 6 seconds, reset timer 3x within that period - - DEFAULT_MIN_STEER_SPEED = 0.4 # m/s, newer EPS racks fault below this speed, don't show a low speed alert - - ACCEL_MAX = 2.0 # 2.0 m/s max acceleration - ACCEL_MIN = -3.5 # 3.5 m/s max deceleration - - def __init__(self, CP): - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - if CP.flags & VolkswagenFlags.PQ: - self.LDW_STEP = 5 # LDW_1 message frequency 20Hz - self.ACC_HUD_STEP = 4 # ACC_GRA_Anzeige frequency 25Hz - self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm - self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) - self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) - - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"] - self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] - - self.BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_Neu", "GRA_Neu_Setzen", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_Neu", "GRA_Recall", [1]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), - Button(car.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), - Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), - ] - - self.LDW_MESSAGES = { - "none": 0, # Nothing to display - "laneAssistUnavail": 1, # "Lane Assist currently not available." - "laneAssistUnavailSysError": 2, # "Lane Assist system error" - "laneAssistUnavailNoSensorView": 3, # "Lane Assist not available. No sensor view." - "laneAssistTakeOver": 4, # "Lane Assist: Please Take Over Steering" - "laneAssistDeactivTrailer": 5, # "Lane Assist: no function with trailer" - } - - else: - self.LDW_STEP = 10 # LDW_02 message frequency 10Hz - self.ACC_HUD_STEP = 6 # ACC_02 message frequency 16Hz - self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm - self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) - self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) - - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"] - elif CP.transmissionType == TransmissionType.direct: - self.shifter_values = can_define.dv["EV_Gearshift"]["GearPosition"] - self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"] - - self.BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), - Button(car.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), - Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), - ] - - self.LDW_MESSAGES = { - "none": 0, # Nothing to display - "laneAssistUnavailChime": 1, # "Lane Assist currently not available." with chime - "laneAssistUnavailNoSensorChime": 3, # "Lane Assist not available. No sensor view." with chime - "laneAssistTakeOverUrgent": 4, # "Lane Assist: Please Take Over Steering" with urgent beep - "emergencyAssistUrgent": 6, # "Emergency Assist: Please Take Over Steering" with urgent beep - "laneAssistTakeOverChime": 7, # "Lane Assist: Please Take Over Steering" with chime - "laneAssistTakeOver": 8, # "Lane Assist: Please Take Over Steering" silent - "emergencyAssistChangingLanes": 9, # "Emergency Assist: Changing lanes..." with urgent beep - "laneAssistDeactivated": 10, # "Lane Assist deactivated." silent with persistent icon afterward - } - - -class CANBUS: - pt = 0 - cam = 2 - - -class WMI(StrEnum): - VOLKSWAGEN_USA_SUV = "1V2" - VOLKSWAGEN_USA_CAR = "1VW" - VOLKSWAGEN_MEXICO_SUV = "3VV" - VOLKSWAGEN_MEXICO_CAR = "3VW" - VOLKSWAGEN_ARGENTINA = "8AW" - VOLKSWAGEN_BRASIL = "9BW" - SAIC_VOLKSWAGEN = "LSV" - SKODA = "TMB" - SEAT = "VSS" - AUDI_EUROPE_MPV = "WA1" - AUDI_GERMANY_CAR = "WAU" - MAN = "WMA" - AUDI_SPORT = "WUA" - VOLKSWAGEN_COMMERCIAL = "WV1" - VOLKSWAGEN_COMMERCIAL_BUS_VAN = "WV2" - VOLKSWAGEN_EUROPE_SUV = "WVG" - VOLKSWAGEN_EUROPE_CAR = "WVW" - VOLKSWAGEN_GROUP_RUS = "XW8" - - -class VolkswagenFlags(IntFlag): - # Detected flags - STOCK_HCA_PRESENT = 1 - - # Static flags - PQ = 2 - - -@dataclass -class VolkswagenMQBPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_mqb_2010', None)) - # Volkswagen uses the VIN WMI and chassis code to match in the absence of the comma power - # on camera-integrated cars, as we lose too many ECUs to reliably identify the vehicle - chassis_codes: set[str] = field(default_factory=set) - wmis: set[WMI] = field(default_factory=set) - - -@dataclass -class VolkswagenPQPlatformConfig(VolkswagenMQBPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_golf_mk4', None)) - - def init(self): - self.flags |= VolkswagenFlags.PQ - - -@dataclass(frozen=True, kw_only=True) -class VolkswagenCarSpecs(CarSpecs): - centerToFrontRatio: float = 0.45 - steerRatio: float = 15.6 - minSteerSpeed: float = CarControllerParams.DEFAULT_MIN_STEER_SPEED - - -class Footnote(Enum): - KAMIQ = CarFootnote( - "Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.", - Column.MODEL) - PASSAT = CarFootnote( - "Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.", - Column.MODEL) - SKODA_HEATED_WINDSHIELD = CarFootnote( - "Some Škoda vehicles are equipped with heated windshields, which are known " + - "to block GPS signal needed for some comma 3X functionality.", - Column.MODEL) - VW_EXP_LONG = CarFootnote( - "Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " + - "are limited to using stock ACC.", - Column.LONGITUDINAL) - VW_MQB_A0 = CarFootnote( - "Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot " + - "in software, but doesn't yet have a harness available from the comma store.", - Column.HARDWARE) - - -@dataclass -class VWCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC) & Lane Assist" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.vw_j533])) - - def init_make(self, CP: car.CarParams): - self.footnotes.append(Footnote.VW_EXP_LONG) - if "SKODA" in CP.carFingerprint: - self.footnotes.append(Footnote.SKODA_HEATED_WINDSHIELD) - - if CP.carFingerprint in (CAR.VOLKSWAGEN_CRAFTER_MK2, CAR.VOLKSWAGEN_TRANSPORTER_T61): - self.car_parts = CarParts([Device.threex_angled_mount, CarHarness.vw_j533]) - - if abs(CP.minSteerSpeed - CarControllerParams.DEFAULT_MIN_STEER_SPEED) < 1e-3: - self.min_steer_speed = 0 - - -# Check the 7th and 8th characters of the VIN before adding a new CAR. If the -# chassis code is already listed below, don't add a new CAR, just add to the -# FW_VERSIONS for that existing CAR. - -class CAR(Platforms): - config: VolkswagenMQBPlatformConfig | VolkswagenPQPlatformConfig - - VOLKSWAGEN_ARTEON_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), - ], - VolkswagenCarSpecs(mass=1733, wheelbase=2.84), - chassis_codes={"AN", "3H"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_ATLAS_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Atlas 2018-23"), - VWCarDocs("Volkswagen Atlas Cross Sport 2020-22"), - VWCarDocs("Volkswagen Teramont 2018-22"), - VWCarDocs("Volkswagen Teramont Cross Sport 2021-22"), - VWCarDocs("Volkswagen Teramont X 2021-22"), - ], - VolkswagenCarSpecs(mass=2011, wheelbase=2.98), - chassis_codes={"CA"}, - wmis={WMI.VOLKSWAGEN_USA_SUV, WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_CADDY_MK3 = VolkswagenPQPlatformConfig( - [ - VWCarDocs("Volkswagen Caddy 2019"), - VWCarDocs("Volkswagen Caddy Maxi 2019"), - ], - VolkswagenCarSpecs(mass=1613, wheelbase=2.6, minSteerSpeed=21 * CV.KPH_TO_MS), - chassis_codes={"2K"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, - ) - VOLKSWAGEN_CRAFTER_MK2 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Crafter 2017-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen e-Crafter 2018-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen Grand California 2019-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN TGE 2017-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN eTGE 2020-24", video_link="https://youtu.be/4100gLeabmo"), - ], - VolkswagenCarSpecs(mass=2100, wheelbase=3.64, minSteerSpeed=50 * CV.KPH_TO_MS), - chassis_codes={"SY", "SZ", "UY", "UZ"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL, WMI.MAN}, - ) - VOLKSWAGEN_GOLF_MK7 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen e-Golf 2014-20"), - VWCarDocs("Volkswagen Golf 2015-20", auto_resume=False), - VWCarDocs("Volkswagen Golf Alltrack 2015-19", auto_resume=False), - VWCarDocs("Volkswagen Golf GTD 2015-20"), - VWCarDocs("Volkswagen Golf GTE 2015-20"), - VWCarDocs("Volkswagen Golf GTI 2015-21", auto_resume=False), - VWCarDocs("Volkswagen Golf R 2015-19"), - VWCarDocs("Volkswagen Golf SportsVan 2015-20"), - ], - VolkswagenCarSpecs(mass=1397, wheelbase=2.62), - chassis_codes={"5G", "AU", "BA", "BE"}, - wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_JETTA_MK7 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Jetta 2018-24"), - VWCarDocs("Volkswagen Jetta GLI 2021-24"), - ], - VolkswagenCarSpecs(mass=1328, wheelbase=2.71), - chassis_codes={"BU"}, - wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_PASSAT_MK8 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]), - VWCarDocs("Volkswagen Passat Alltrack 2015-22"), - VWCarDocs("Volkswagen Passat GTE 2015-22"), - ], - VolkswagenCarSpecs(mass=1551, wheelbase=2.79), - chassis_codes={"3C", "3G"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_PASSAT_NMS = VolkswagenPQPlatformConfig( - [VWCarDocs("Volkswagen Passat NMS 2017-22")], - VolkswagenCarSpecs(mass=1503, wheelbase=2.80, minSteerSpeed=50 * CV.KPH_TO_MS, minEnableSpeed=20 * CV.KPH_TO_MS), - chassis_codes={"A3"}, - wmis={WMI.VOLKSWAGEN_USA_CAR}, - ) - VOLKSWAGEN_POLO_MK6 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Polo 2018-23", footnotes=[Footnote.VW_MQB_A0]), - VWCarDocs("Volkswagen Polo GTI 2018-23", footnotes=[Footnote.VW_MQB_A0]), - ], - VolkswagenCarSpecs(mass=1230, wheelbase=2.55), - chassis_codes={"AW"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_SHARAN_MK2 = VolkswagenPQPlatformConfig( - [ - VWCarDocs("Volkswagen Sharan 2018-22"), - VWCarDocs("SEAT Alhambra 2018-20"), - ], - VolkswagenCarSpecs(mass=1639, wheelbase=2.92, minSteerSpeed=50 * CV.KPH_TO_MS), - chassis_codes={"7N"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_TAOS_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen Taos 2022-23")], - VolkswagenCarSpecs(mass=1498, wheelbase=2.69), - chassis_codes={"B2"}, - wmis={WMI.VOLKSWAGEN_MEXICO_SUV, WMI.VOLKSWAGEN_ARGENTINA}, - ) - VOLKSWAGEN_TCROSS_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0])], - VolkswagenCarSpecs(mass=1150, wheelbase=2.60), - chassis_codes={"C1"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_TIGUAN_MK2 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Tiguan 2018-24"), - VWCarDocs("Volkswagen Tiguan eHybrid 2021-23"), - ], - VolkswagenCarSpecs(mass=1715, wheelbase=2.74), - chassis_codes={"5N", "AD", "AX", "BW"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV, WMI.VOLKSWAGEN_MEXICO_SUV}, - ) - VOLKSWAGEN_TOURAN_MK2 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen Touran 2016-23")], - VolkswagenCarSpecs(mass=1516, wheelbase=2.79), - chassis_codes={"1T"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_TRANSPORTER_T61 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Caravelle 2020"), - VWCarDocs("Volkswagen California 2021-23"), - ], - VolkswagenCarSpecs(mass=1926, wheelbase=3.00, minSteerSpeed=14.0), - chassis_codes={"7H", "7L"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, - ) - VOLKSWAGEN_TROC_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen T-Roc 2018-23")], - VolkswagenCarSpecs(mass=1413, wheelbase=2.63), - chassis_codes={"A1"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - AUDI_A3_MK3 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Audi A3 2014-19"), - VWCarDocs("Audi A3 Sportback e-tron 2017-18"), - VWCarDocs("Audi RS3 2018"), - VWCarDocs("Audi S3 2015-17"), - ], - VolkswagenCarSpecs(mass=1335, wheelbase=2.61), - chassis_codes={"8V", "FF"}, - wmis={WMI.AUDI_GERMANY_CAR, WMI.AUDI_SPORT}, - ) - AUDI_Q2_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Audi Q2 2018")], - VolkswagenCarSpecs(mass=1205, wheelbase=2.61), - chassis_codes={"GA"}, - wmis={WMI.AUDI_GERMANY_CAR}, - ) - AUDI_Q3_MK2 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Audi Q3 2019-23")], - VolkswagenCarSpecs(mass=1623, wheelbase=2.68), - chassis_codes={"8U", "F3", "FS"}, - wmis={WMI.AUDI_EUROPE_MPV, WMI.AUDI_GERMANY_CAR}, - ) - SEAT_ATECA_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("CUPRA Ateca 2018-23"), - VWCarDocs("SEAT Ateca 2016-23"), - VWCarDocs("SEAT Leon 2014-20"), - ], - VolkswagenCarSpecs(mass=1300, wheelbase=2.64), - chassis_codes={"5F"}, - wmis={WMI.SEAT}, - ) - SKODA_FABIA_MK4 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Fabia 2022-23", footnotes=[Footnote.VW_MQB_A0])], - VolkswagenCarSpecs(mass=1266, wheelbase=2.56), - chassis_codes={"PJ"}, - wmis={WMI.SKODA}, - ) - SKODA_KAMIQ_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Škoda Kamiq 2021-23", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]), - VWCarDocs("Škoda Scala 2020-23", footnotes=[Footnote.VW_MQB_A0]), - ], - VolkswagenCarSpecs(mass=1230, wheelbase=2.66), - chassis_codes={"NW"}, - wmis={WMI.SKODA}, - ) - SKODA_KAROQ_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Karoq 2019-23")], - VolkswagenCarSpecs(mass=1278, wheelbase=2.66), - chassis_codes={"NU"}, - wmis={WMI.SKODA}, - ) - SKODA_KODIAQ_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Kodiaq 2017-23")], - VolkswagenCarSpecs(mass=1569, wheelbase=2.79), - chassis_codes={"NS"}, - wmis={WMI.SKODA, WMI.VOLKSWAGEN_GROUP_RUS}, - ) - SKODA_OCTAVIA_MK3 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Škoda Octavia 2015-19"), - VWCarDocs("Škoda Octavia RS 2016"), - VWCarDocs("Škoda Octavia Scout 2017-19"), - ], - VolkswagenCarSpecs(mass=1388, wheelbase=2.68), - chassis_codes={"NE"}, - wmis={WMI.SKODA}, - ) - SKODA_SUPERB_MK3 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Superb 2015-22")], - VolkswagenCarSpecs(mass=1505, wheelbase=2.84), - chassis_codes={"3V", "NP"}, - wmis={WMI.SKODA}, - ) - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - candidates = set() - - # Compile all FW versions for each ECU - all_ecu_versions: dict[EcuAddrSubAddr, set[str]] = defaultdict(set) - for ecus in offline_fw_versions.values(): - for ecu, versions in ecus.items(): - all_ecu_versions[ecu] |= set(versions) - - # Check the WMI and chassis code to determine the platform - wmi = vin[:3] - chassis_code = vin[6:8] - - for platform in CAR: - valid_ecus = set() - for ecu in offline_fw_versions[platform]: - addr = ecu[1:] - if ecu[0] not in CHECK_FUZZY_ECUS: - continue - - # Sanity check that live FW is in the superset of all FW, Volkswagen ECU part numbers are commonly shared - found_versions = live_fw_versions.get(addr, []) - expected_versions = all_ecu_versions[ecu] - if not any(found_version in expected_versions for found_version in found_versions): - break - - valid_ecus.add(ecu[0]) - - if valid_ecus != CHECK_FUZZY_ECUS: - continue - - if wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes: - candidates.add(platform) - - return {str(c) for c in candidates} - - -# These ECUs are required to match to gain a VIN match -# TODO: do we want to check camera when we add its FW? -CHECK_FUZZY_ECUS = {Ecu.fwdRadar} - -# All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars -# with a manual trans won't return transmission firmware, but all other cars will. -# -# The 0xF187 SW part number query should return in the form of N[NX][NX] NNN NNN [X[X]], -# where N=number, X=letter, and the trailing two letters are optional. Performance -# tuners sometimes tamper with that field (e.g. 8V0 9C0 BB0 1 from COBB/EQT). Tampered -# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have -# them repaired by the tuner before including them in openpilot. - -VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -VOLKSWAGEN_RX_OFFSET = 0x6a - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, obd_multiplexing in [(1, True), (1, False), (0, False)] for request in [ - Request( - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar, Ecu.fwdCamera], - rx_offset=VOLKSWAGEN_RX_OFFSET, - bus=bus, - obd_multiplexing=obd_multiplexing, - ), - Request( - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - bus=bus, - obd_multiplexing=obd_multiplexing, - ), - ]], - non_essential_ecus={Ecu.eps: list(CAR)}, - extra_ecus=[(Ecu.fwdCamera, 0x74f, None)], - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4dd60faa063dfe..c30b458ef5ed84 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -18,7 +18,7 @@ from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.car.car_helpers import get_car_interface +from opendbc.car.car_helpers import get_car_interface from openpilot.selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert from openpilot.selfdrive.controls.lib.drive_helpers import VCruiseHelper, clip_curvature, get_startup_event from openpilot.selfdrive.controls.lib.events import Events, ET @@ -28,6 +28,7 @@ from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel +from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.system.hardware import HARDWARE @@ -78,6 +79,11 @@ def __init__(self, CI=None): # Setup sockets self.pm = messaging.PubMaster(['controlsState', 'carControl', 'onroadEvents']) + if self.params.get_bool("UbloxAvailable"): + self.gps_location_service = "gpsLocationExternal" + else: + self.gps_location_service = "gpsLocation" + self.gps_packets = [self.gps_location_service] self.sensor_packets = ["accelerometer", "gyroscope"] self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] @@ -86,16 +92,16 @@ def __init__(self, CI=None): # TODO: de-couple controlsd with card/conflate on carState without introducing controls mismatches self.car_state_sock = messaging.sub_sock('carState', timeout=20) - ignore = self.sensor_packets + ['testJoystick'] + ignore = self.sensor_packets + self.gps_packets + ['testJoystick'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] if REPLAY: # no vipc in replay will make them ignored anyways ignore += ['roadCameraState', 'wideRoadCameraState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', - 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman', + 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'testJoystick'] + self.camera_packets + self.sensor_packets, + 'testJoystick'] + self.camera_packets + self.sensor_packets + self.gps_packets, ignore_alive=ignore, ignore_avg_freq=ignore+['radarState', 'testJoystick'], ignore_valid=['testJoystick', ], frequency=int(1/DT_CTRL)) @@ -120,6 +126,9 @@ def __init__(self, CI=None): self.AM = AlertManager() self.events = Events() + self.pose_calibrator = PoseCalibrator() + self.calibrated_pose: Pose|None = None + self.LoC = LongControl(self.CP) self.VM = VehicleModel(self.CP) @@ -335,11 +344,9 @@ def update_events(self, CS): self.logged_comm_issue = None if not (self.CP.notCar and self.joystick_mode): - if not self.sm['liveLocationKalman'].posenetOK: + if not self.sm['livePose'].posenetOK: self.events.add(EventName.posenetInvalid) - if not self.sm['liveLocationKalman'].deviceStable: - self.events.add(EventName.deviceFalling) - if not self.sm['liveLocationKalman'].inputsOK: + if not self.sm['livePose'].inputsOK: self.events.add(EventName.locationdTemporaryError) if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): self.events.add(EventName.paramsdTemporaryError) @@ -375,10 +382,11 @@ def update_events(self, CS): # TODO: fix simulator if not SIMULATION or REPLAY: - # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes - if not self.sm['liveLocationKalman'].gpsOK and self.sm['liveLocationKalman'].inputsOK and (self.distance_traveled > 1500): + # Not show in first 1.5 km to allow for driving out of garage. This event shows after 5 minutes + gps_ok = self.sm.recv_frame[self.gps_location_service] > 0 and (self.sm.frame - self.sm.recv_frame[self.gps_location_service]) * DT_CTRL < 2.0 + if not gps_ok and self.sm['livePose'].inputsOK and (self.distance_traveled > 1500): self.events.add(EventName.noGps) - if self.sm['liveLocationKalman'].gpsOK: + if gps_ok: self.distance_traveled = 0 self.distance_traveled += CS.vEgo * DT_CTRL @@ -429,6 +437,13 @@ def data_sample(self): if ps.safetyModel not in IGNORED_SAFETY_MODES): self.mismatch_counter += 1 + # calibrate the live pose and save it for later use + if self.sm.updated["liveCalibration"]: + self.pose_calibrator.feed_live_calib(self.sm['liveCalibration']) + if self.sm.updated["livePose"]: + device_pose = Pose.from_live_pose(self.sm['livePose']) + self.calibrated_pose = self.pose_calibrator.build_calibrated_pose(device_pose) + return CS def state_transition(self, CS): @@ -573,7 +588,7 @@ def state_control(self, CS): actuators.curvature = self.desired_curvature actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, self.steer_limited, self.desired_curvature, - self.sm['liveLocationKalman']) + self.calibrated_pose) # TODO what if not available else: lac_log = log.ControlsState.LateralDebugState.new_message() if self.sm.recv_frame['testJoystick'] > 0: @@ -650,12 +665,9 @@ def publish_logs(self, CS, start_time, CC, lac_log): # Orientation and angle rates can be useful for carcontroller # Only calibrated (car) frame is relevant for the carcontroller - orientation_value = list(self.sm['liveLocationKalman'].calibratedOrientationNED.value) - if len(orientation_value) > 2: - CC.orientationNED = orientation_value - angular_rate_value = list(self.sm['liveLocationKalman'].angularVelocityCalibrated.value) - if len(angular_rate_value) > 2: - CC.angularVelocity = angular_rate_value + if self.calibrated_pose is not None: + CC.orientationNED = self.calibrated_pose.orientation.xyz.tolist() + CC.angularVelocity = self.calibrated_pose.angular_velocity.xyz.tolist() CC.cruiseControl.override = self.enabled and not CC.longActive and self.CP.openpilotLongitudinalControl CC.cruiseControl.cancel = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index fddb331ccb9c7d..0e4a27da61725f 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -17,7 +17,7 @@ def __init__(self, CP, CI): self.steer_max = 1.0 @abstractmethod - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): pass def reset(self): diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index 329c486eb9a2e5..d3da656daa16df 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -11,7 +11,7 @@ def __init__(self, CP, CI): super().__init__(CP, CI) self.sat_check_min_speed = 5. - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): angle_log = log.ControlsState.LateralAngleState.new_message() if not active: diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index 9e6160838b2067..5b29958b6967cb 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -17,7 +17,7 @@ def reset(self): super().reset() self.pid.reset() - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): pid_log = log.ControlsState.LateralPIDState.new_message() pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index decff2ec054283..1c4fd7979e6338 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -1,8 +1,8 @@ import math from cereal import log +from opendbc.car.interfaces import LatControlInputs from openpilot.common.numpy_fast import interp -from openpilot.selfdrive.car.interfaces import LatControlInputs from openpilot.selfdrive.controls.lib.latcontrol import LatControl from openpilot.selfdrive.controls.lib.pid import PIDController from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY @@ -37,7 +37,7 @@ def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction): self.torque_params.latAccelOffset = latAccelOffset self.torque_params.friction = friction - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): pid_log = log.ControlsState.LateralTorqueState.new_message() if not active: output_torque = 0.0 @@ -49,8 +49,9 @@ def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): actual_curvature = actual_curvature_vm curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) else: - actual_curvature_llk = llk.angularVelocityCalibrated.value[2] / CS.vEgo - actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_llk]) + assert calibrated_pose is not None + actual_curvature_pose = calibrated_pose.angular_velocity.yaw / CS.vEgo + actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_pose]) curvature_deadzone = 0.0 desired_lateral_accel = desired_curvature * CS.vEgo ** 2 diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index bad37add63aab3..fa6d5542bdf71b 100755 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -3,12 +3,12 @@ import time import numpy as np from cereal import log +from opendbc.car.interfaces import ACCEL_MIN from openpilot.common.numpy_fast import clip from openpilot.common.realtime import DT_MDL from openpilot.common.swaglog import cloudlog # WARNING: imports outside of constants will not trigger a rebuild from openpilot.selfdrive.modeld.constants import index_function -from openpilot.selfdrive.car.interfaces import ACCEL_MIN from openpilot.selfdrive.controls.radard import _LEAD_ACCEL_TAU if __name__ == '__main__': # generating code diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 6a2a1570d866f1..528ecdec68c734 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -4,11 +4,11 @@ from openpilot.common.numpy_fast import clip, interp import cereal.messaging as messaging +from opendbc.car.interfaces import ACCEL_MIN, ACCEL_MAX from openpilot.common.conversions import Conversions as CV from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.realtime import DT_MDL from openpilot.selfdrive.modeld.constants import ModelConstants -from openpilot.selfdrive.car.interfaces import ACCEL_MIN, ACCEL_MAX from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py index e12da6ed97f20e..c3847ed1a5c9c7 100644 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/lib/tests/test_latcontrol.py @@ -1,15 +1,17 @@ from parameterized import parameterized from cereal import car, log -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN +from opendbc.car.car_helpers import interfaces +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.nissan.values import CAR as NISSAN +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel -from openpilot.common.mock.generators import generate_liveLocationKalman +from openpilot.selfdrive.locationd.helpers import Pose +from openpilot.common.mock.generators import generate_livePose class TestLatControl: @@ -19,6 +21,7 @@ def test_saturation(self, car_name, controller): CarInterface, CarController, CarState = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) CI = CarInterface(CP, CarController, CarState) + CP = convert_to_capnp(CP) VM = VehicleModel(CP) controller = controller(CP.as_reader(), CI) @@ -29,8 +32,10 @@ def test_saturation(self, car_name, controller): params = log.LiveParametersData.new_message() - llk = generate_liveLocationKalman() + lp = generate_livePose() + pose = Pose.from_live_pose(lp.livePose) + for _ in range(1000): - _, _, lac_log = controller.update(True, CS, VM, params, False, 1, llk) + _, _, lac_log = controller.update(True, CS, VM, params, False, 1, pose) assert lac_log.saturated diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py index f666f875a69d95..b58bdbe522a441 100644 --- a/selfdrive/controls/lib/tests/test_vehicle_model.py +++ b/selfdrive/controls/lib/tests/test_vehicle_model.py @@ -3,15 +3,16 @@ import numpy as np -from openpilot.selfdrive.car.honda.interface import CarInterface -from openpilot.selfdrive.car.honda.values import CAR +from opendbc.car.honda.interface import CarInterface +from opendbc.car.honda.values import CAR +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel, dyn_ss_sol, create_dyn_state_matrices class TestVehicleModel: def setup_method(self): CP = CarInterface.get_non_essential_params(CAR.HONDA_CIVIC) - self.VM = VehicleModel(CP) + self.VM = VehicleModel(convert_to_capnp(CP)) def test_round_trip_yaw_rate(self): # TODO: fix VM to work at zero speed diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index a7e3c0211d3ec7..f3aa099bfbf6ba 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -6,6 +6,7 @@ import capnp from cereal import messaging, log, car +from opendbc.car import structs from openpilot.common.numpy_fast import interp from openpilot.common.params import Params from openpilot.common.realtime import DT_CTRL, Ratekeeper, Priority, config_realtime_process @@ -208,23 +209,17 @@ def __init__(self, radar_ts: float, delay: int = 0): self.ready = False - def update(self, sm: messaging.SubMaster, rr): + def update(self, sm: messaging.SubMaster, rr: structs.RadarData): self.ready = sm.seen['modelV2'] self.current_time = 1e-9*max(sm.logMonoTime.values()) - radar_points = [] - radar_errors = [] - if rr is not None: - radar_points = rr.points - radar_errors = rr.errors - if sm.recv_frame['carState'] != self.last_v_ego_frame: self.v_ego = sm['carState'].vEgo self.v_ego_hist.append(self.v_ego) self.last_v_ego_frame = sm.recv_frame['carState'] ar_pts = {} - for pt in radar_points: + for pt in rr.points: ar_pts[pt.trackId] = [pt.dRel, pt.yRel, pt.vRel, pt.measured] # *** remove missing points from meta data *** @@ -245,10 +240,10 @@ def update(self, sm: messaging.SubMaster, rr): self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3]) # *** publish radarState *** - self.radar_state_valid = sm.all_checks() and len(radar_errors) == 0 + self.radar_state_valid = sm.all_checks() and len(rr.errors) == 0 self.radar_state = log.RadarState.new_message() self.radar_state.mdMonoTime = sm.logMonoTime['modelV2'] - self.radar_state.radarErrors = list(radar_errors) + self.radar_state.radarErrors = list(rr.errors) self.radar_state.carStateMonoTime = sm.logMonoTime['carState'] if len(sm['modelV2'].temporalPose.trans): @@ -283,7 +278,7 @@ def publish(self, pm: messaging.PubMaster, lag_ms: float): # fuses camera and radar data for best lead detection -def main(): +def main() -> None: config_realtime_process(5, Priority.CTRL_LOW) # wait for stats about the car to come in from controls @@ -293,7 +288,7 @@ def main(): # import the radar from the fingerprint cloudlog.info("radard is importing %s", CP.carName) - RadarInterface = importlib.import_module(f'selfdrive.car.{CP.carName}.radar_interface').RadarInterface + RadarInterface = importlib.import_module(f'opendbc.car.{CP.carName}.radar_interface').RadarInterface # *** setup messaging can_sock = messaging.sub_sock('can') @@ -307,7 +302,7 @@ def main(): while 1: can_strings = messaging.drain_sock_raw(can_sock, wait_for_one=True) - rr = RI.update(can_capnp_to_list(can_strings)) + rr: structs.RadarData | None = RI.update(can_capnp_to_list(can_strings)) sm.update(0) if rr is None: continue diff --git a/selfdrive/controls/tests/test_leads.py b/selfdrive/controls/tests/test_leads.py index f1f4449afdc4b9..4b98628bf6e847 100644 --- a/selfdrive/controls/tests/test_leads.py +++ b/selfdrive/controls/tests/test_leads.py @@ -1,7 +1,7 @@ import cereal.messaging as messaging +from opendbc.car.toyota.values import CAR as TOYOTA from openpilot.selfdrive.test.process_replay import replay_process_with_name -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA class TestLeads: diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py index 51b9887c96bfff..077d2890215bc8 100644 --- a/selfdrive/controls/tests/test_startup.py +++ b/selfdrive/controls/tests/test_startup.py @@ -3,11 +3,11 @@ from cereal import log, car import cereal.messaging as messaging +from opendbc.car.fingerprints import _FINGERPRINTS +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.mazda.values import CAR as MAZDA from openpilot.common.params import Params from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp -from openpilot.selfdrive.car.fingerprints import _FINGERPRINTS -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA from openpilot.selfdrive.controls.lib.events import EVENT_NAME from openpilot.system.manager.process_config import managed_processes diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/controls/tests/test_state_machine.py index b6ec512dc4ab0a..a480aa8d2b4d5b 100644 --- a/selfdrive/controls/tests/test_state_machine.py +++ b/selfdrive/controls/tests/test_state_machine.py @@ -1,10 +1,10 @@ from cereal import car, log +from opendbc.car.car_helpers import interfaces +from opendbc.car.mock.values import CAR as MOCK from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car.car_helpers import interfaces from openpilot.selfdrive.controls.controlsd import Controls, SOFT_DISABLE_TIME from openpilot.selfdrive.controls.lib.events import Events, ET, Alert, Priority, AlertSize, AlertStatus, VisualAlert, \ AudibleAlert, EVENTS -from openpilot.selfdrive.car.mock.values import CAR as MOCK State = log.ControlsState.OpenpilotState diff --git a/selfdrive/debug/adb.sh b/selfdrive/debug/adb.sh index 919a82fefc726b..8fa267fd4d0d41 100755 --- a/selfdrive/debug/adb.sh +++ b/selfdrive/debug/adb.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e PORT=5555 diff --git a/selfdrive/debug/car/disable_ecu.py b/selfdrive/debug/car/disable_ecu.py new file mode 100755 index 00000000000000..185139324d610f --- /dev/null +++ b/selfdrive/debug/car/disable_ecu.py @@ -0,0 +1,15 @@ +#!/usr/bin/env python3 +import time +import cereal.messaging as messaging +from opendbc.car.disable_ecu import disable_ecu +from openpilot.selfdrive.car.card import can_comm_callbacks + +if __name__ == "__main__": + sendcan = messaging.pub_sock('sendcan') + logcan = messaging.sub_sock('can') + can_callbacks = can_comm_callbacks(logcan, sendcan) + time.sleep(1) + + # honda bosch radar disable + disabled = disable_ecu(*can_callbacks, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03', timeout=0.5, debug=False) + print(f"disabled: {disabled}") diff --git a/selfdrive/debug/car/ecu_addrs.py b/selfdrive/debug/car/ecu_addrs.py new file mode 100755 index 00000000000000..58781222dc4be8 --- /dev/null +++ b/selfdrive/debug/car/ecu_addrs.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python3 +import argparse +import time +import cereal.messaging as messaging +from opendbc.car.ecu_addrs import get_all_ecu_addrs +from openpilot.common.params import Params +from openpilot.selfdrive.car.card import can_comm_callbacks, obd_callback + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Get addresses of all ECUs') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--bus', type=int, default=1) + parser.add_argument('--no-obd', action='store_true') + parser.add_argument('--timeout', type=float, default=1.0) + args = parser.parse_args() + + logcan = messaging.sub_sock('can') + sendcan = messaging.pub_sock('sendcan') + can_callbacks = can_comm_callbacks(logcan, sendcan) + + # Set up params for pandad + params = Params() + params.remove("FirmwareQueryDone") + params.put_bool("IsOnroad", False) + time.sleep(0.2) # thread is 10 Hz + params.put_bool("IsOnroad", True) + + obd_callback(params)(not args.no_obd) + + print("Getting ECU addresses ...") + ecu_addrs = get_all_ecu_addrs(*can_callbacks, args.bus, args.timeout, debug=args.debug) + + print() + print("Found ECUs on rx addresses:") + for addr, subaddr, _ in ecu_addrs: + msg = f" {hex(addr)}" + if subaddr is not None: + msg += f" (sub-address: {hex(subaddr)})" + print(msg) diff --git a/selfdrive/debug/car/fw_versions.py b/selfdrive/debug/car/fw_versions.py new file mode 100755 index 00000000000000..18a287b38e09ed --- /dev/null +++ b/selfdrive/debug/car/fw_versions.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python3 +import time +import argparse +import cereal.messaging as messaging +from cereal import car +from opendbc.car.fw_versions import get_fw_versions, match_fw_to_car +from opendbc.car.vin import get_vin +from openpilot.common.params import Params +from openpilot.selfdrive.car.card import can_comm_callbacks, obd_callback +from typing import Any + +Ecu = car.CarParams.Ecu + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Get firmware version of ECUs') + parser.add_argument('--scan', action='store_true') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--brand', help='Only query addresses/with requests for this brand') + args = parser.parse_args() + + logcan = messaging.sub_sock('can') + pandaStates_sock = messaging.sub_sock('pandaStates') + sendcan = messaging.pub_sock('sendcan') + can_callbacks = can_comm_callbacks(logcan, sendcan) + + # Set up params for pandad + params = Params() + params.remove("FirmwareQueryDone") + params.put_bool("IsOnroad", False) + time.sleep(0.2) # thread is 10 Hz + params.put_bool("IsOnroad", True) + set_obd_multiplexing = obd_callback(params) + + extra: Any = None + if args.scan: + extra = {} + # Honda + for i in range(256): + extra[(Ecu.unknown, 0x18da00f1 + (i << 8), None)] = [] + extra[(Ecu.unknown, 0x700 + i, None)] = [] + extra[(Ecu.unknown, 0x750, i)] = [] + extra = {"any": {"debug": extra}} + + num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates) + + t = time.time() + print("Getting vin...") + set_obd_multiplexing(True) + vin_rx_addr, vin_rx_bus, vin = get_vin(*can_callbacks, (0, 1), debug=args.debug) + print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') + print(f"Getting VIN took {time.time() - t:.3f} s") + print() + + t = time.time() + fw_vers = get_fw_versions(*can_callbacks, set_obd_multiplexing, query_brand=args.brand, extra=extra, num_pandas=num_pandas, debug=args.debug, progress=True) + _, candidates = match_fw_to_car(fw_vers, vin) + + print() + print("Found FW versions") + print("{") + padding = max([len(fw.brand) for fw in fw_vers] or [0]) + for version in fw_vers: + subaddr = None if version.subAddress == 0 else hex(version.subAddress) + print(f" Brand: {version.brand:{padding}}, bus: {version.bus}, OBD: {version.obdMultiplexing} - " + + f"(Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion!r}]") + print("}") + + print() + print("Possible matches:", candidates) + print(f"Getting fw took {time.time() - t:.3f} s") diff --git a/selfdrive/debug/car/vin.py b/selfdrive/debug/car/vin.py new file mode 100755 index 00000000000000..7946b429e45af6 --- /dev/null +++ b/selfdrive/debug/car/vin.py @@ -0,0 +1,22 @@ +#!/usr/bin/env python3 +import argparse +import time +import cereal.messaging as messaging +from opendbc.car.vin import get_vin +from openpilot.selfdrive.car.card import can_comm_callbacks + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Get VIN of the car') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--bus', type=int, default=1) + parser.add_argument('--timeout', type=float, default=0.1) + parser.add_argument('--retry', type=int, default=5) + args = parser.parse_args() + + sendcan = messaging.pub_sock('sendcan') + logcan = messaging.sub_sock('can') + can_callbacks = can_comm_callbacks(logcan, sendcan) + time.sleep(1) + + vin_rx_addr, vin_rx_bus, vin = get_vin(*can_callbacks, (args.bus,), args.timeout, args.retry, debug=args.debug) + print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index 93b0430c1e0c0f..efe01b7d7ec906 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -4,8 +4,8 @@ from cereal import car, log import cereal.messaging as messaging +from opendbc.car.honda.interface import CarInterface from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car.honda.interface import CarInterface from openpilot.selfdrive.controls.lib.events import ET, Events from openpilot.selfdrive.controls.lib.alertmanager import AlertManager from openpilot.system.manager.process_config import managed_processes @@ -54,7 +54,7 @@ def cycle_alerts(duration=200, is_metric=False): CS = car.CarState.new_message() CP = CarInterface.get_non_essential_params("HONDA_CIVIC") sm = messaging.SubMaster(['deviceState', 'pandaStates', 'roadCameraState', 'modelV2', 'liveCalibration', - 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman', + 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'managerState'] + cameras) pm = messaging.PubMaster(['controlsState', 'pandaStates', 'deviceState']) diff --git a/selfdrive/debug/dump_car_docs.py b/selfdrive/debug/dump_car_docs.py index f09c602cffa5a3..f0e99cda24ad6f 100755 --- a/selfdrive/debug/dump_car_docs.py +++ b/selfdrive/debug/dump_car_docs.py @@ -2,7 +2,7 @@ import argparse import pickle -from openpilot.selfdrive.car.docs import get_all_car_docs +from opendbc.car.docs import get_all_car_docs def dump_car_docs(path): diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py index 2a5e4e60802e5a..ae1ed06b75ae18 100755 --- a/selfdrive/debug/format_fingerprints.py +++ b/selfdrive/debug/format_fingerprints.py @@ -2,28 +2,24 @@ import jinja2 import os -from cereal import car from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car.interfaces import get_interface_attr - -Ecu = car.CarParams.Ecu +from opendbc.car.interfaces import get_interface_attr CARS = get_interface_attr('CAR') FW_VERSIONS = get_interface_attr('FW_VERSIONS') FINGERPRINTS = get_interface_attr('FINGERPRINTS') -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} FINGERPRINTS_PY_TEMPLATE = jinja2.Template(""" {%- if FINGERPRINTS[brand] %} # ruff: noqa: E501 {% endif %} {% if FW_VERSIONS[brand] %} -from cereal import car +from opendbc.car.structs import CarParams {% endif %} -from openpilot.selfdrive.car.{{brand}}.values import CAR +from opendbc.car.{{brand}}.values import CAR {% if FW_VERSIONS[brand] %} -Ecu = car.CarParams.Ecu +Ecu = CarParams.Ecu {% endif %} {% if comments +%} {{ comments | join() }} @@ -49,7 +45,7 @@ {% for car, _ in FW_VERSIONS[brand].items() %} CAR.{{car.name}}: { {% for key, fw_versions in FW_VERSIONS[brand][car].items() %} - (Ecu.{{ECU_NAME[key[0]]}}, 0x{{"%0x" | format(key[1] | int)}}, \ + (Ecu.{{key[0]}}, 0x{{"%0x" | format(key[1] | int)}}, \ {% if key[2] %}0x{{"%0x" | format(key[2] | int)}}{% else %}{{key[2]}}{% endif %}): [ {% for fw_version in (fw_versions + extra_fw_versions.get(car, {}).get(key, [])) | unique | sort %} {{fw_version}}, @@ -66,14 +62,13 @@ def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tuple, list[bytes]]] = None): extra_fw_versions = extra_fw_versions or {} - fingerprints_file = os.path.join(BASEDIR, f"selfdrive/car/{brand}/fingerprints.py") + fingerprints_file = os.path.join(BASEDIR, f"opendbc/car/{brand}/fingerprints.py") with open(fingerprints_file) as f: comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] with open(fingerprints_file, "w") as f: - f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, ECU_NAME=ECU_NAME, - FINGERPRINTS=FINGERPRINTS, FW_VERSIONS=FW_VERSIONS, - extra_fw_versions=extra_fw_versions)) + f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, FINGERPRINTS=FINGERPRINTS, + FW_VERSIONS=FW_VERSIONS, extra_fw_versions=extra_fw_versions)) if __name__ == "__main__": diff --git a/selfdrive/debug/internal/fuzz_fw_fingerprint.py b/selfdrive/debug/internal/fuzz_fw_fingerprint.py index aedb3ada1dcdd4..fa99e6bfbe8e9e 100755 --- a/selfdrive/debug/internal/fuzz_fw_fingerprint.py +++ b/selfdrive/debug/internal/fuzz_fw_fingerprint.py @@ -5,11 +5,11 @@ from tqdm import tqdm -from openpilot.selfdrive.car.fw_versions import match_fw_to_car_fuzzy -from openpilot.selfdrive.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS -from openpilot.selfdrive.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS -from openpilot.selfdrive.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS -from openpilot.selfdrive.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS +from opendbc.car.fw_versions import match_fw_to_car_fuzzy +from opendbc.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS +from opendbc.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS +from opendbc.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS +from opendbc.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS FWS = {} diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py index 7ef89a6ecae72c..388acf3af58020 100755 --- a/selfdrive/debug/print_docs_diff.py +++ b/selfdrive/debug/print_docs_diff.py @@ -4,8 +4,8 @@ import difflib import pickle -from openpilot.selfdrive.car.docs import get_all_car_docs -from openpilot.selfdrive.car.docs_definitions import Column +from opendbc.car.docs import get_all_car_docs +from opendbc.car.docs_definitions import Column FOOTNOTE_TAG = "{}" STAR_ICON = ' None: def get_msg(self, valid: bool, with_points: bool) -> log.Event: raise NotImplementedError + + +class Measurement: + x, y, z = (property(lambda self: self.xyz[0]), property(lambda self: self.xyz[1]), property(lambda self: self.xyz[2])) + x_std, y_std, z_std = (property(lambda self: self.xyz_std[0]), property(lambda self: self.xyz_std[1]), property(lambda self: self.xyz_std[2])) + roll, pitch, yaw = x, y, z + roll_std, pitch_std, yaw_std = x_std, y_std, z_std + + def __init__(self, xyz: np.ndarray, xyz_std: np.ndarray): + self.xyz: np.ndarray = xyz + self.xyz_std: np.ndarray = xyz_std + + @classmethod + def from_measurement_xyz(cls, measurement: log.LivePose.XYZMeasurement) -> 'Measurement': + return cls( + xyz=np.array([measurement.x, measurement.y, measurement.z]), + xyz_std=np.array([measurement.xStd, measurement.yStd, measurement.zStd]) + ) + + +class Pose: + def __init__(self, orientation: Measurement, velocity: Measurement, acceleration: Measurement, angular_velocity: Measurement): + self.orientation = orientation + self.velocity = velocity + self.acceleration = acceleration + self.angular_velocity = angular_velocity + + @classmethod + def from_live_pose(cls, live_pose: log.LivePose) -> 'Pose': + return Pose( + orientation=Measurement.from_measurement_xyz(live_pose.orientationNED), + velocity=Measurement.from_measurement_xyz(live_pose.velocityDevice), + acceleration=Measurement.from_measurement_xyz(live_pose.accelerationDevice), + angular_velocity=Measurement.from_measurement_xyz(live_pose.angularVelocityDevice) + ) + + +class PoseCalibrator: + def __init__(self): + self.calib_valid = False + self.calib_from_device = np.eye(3) + + def _transform_calib_from_device(self, meas: Measurement): + new_xyz = self.calib_from_device @ meas.xyz + new_xyz_std = rotate_std(self.calib_from_device, meas.xyz_std) + return Measurement(new_xyz, new_xyz_std) + + def _ned_from_calib(self, orientation: Measurement): + ned_from_device = rot_from_euler(orientation.xyz) + ned_from_calib = ned_from_device @ self.calib_from_device.T + ned_from_calib_euler_meas = Measurement(euler_from_rot(ned_from_calib), np.full(3, np.nan)) + return ned_from_calib_euler_meas + + def build_calibrated_pose(self, pose: Pose) -> Pose: + ned_from_calib_euler = self._ned_from_calib(pose.orientation) + angular_velocity_calib = self._transform_calib_from_device(pose.angular_velocity) + acceleration_calib = self._transform_calib_from_device(pose.acceleration) + velocity_calib = self._transform_calib_from_device(pose.angular_velocity) + + return Pose(ned_from_calib_euler, velocity_calib, acceleration_calib, angular_velocity_calib) + + def feed_live_calib(self, live_calib: log.LiveCalibrationData): + calib_rpy = np.array(live_calib.rpyCalib) + device_from_calib = rot_from_euler(calib_rpy) + self.calib_from_device = device_from_calib.T + self.calib_valid = live_calib.calStatus == log.LiveCalibrationData.Status.calibrated diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 1d5749cf34078e..19ded3b4f7176b 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -9,10 +9,9 @@ from openpilot.common.params import Params from openpilot.common.realtime import config_realtime_process, DT_MDL from openpilot.common.numpy_fast import clip -from openpilot.common.transformations.orientation import rot_from_euler from openpilot.selfdrive.locationd.models.car_kf import CarKalman, ObservationKind, States from openpilot.selfdrive.locationd.models.constants import GENERATED_DIR -from openpilot.selfdrive.locationd.helpers import rotate_std +from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.common.swaglog import cloudlog @@ -40,9 +39,8 @@ def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset, P_initial=No self.kf.filter.set_global("stiffness_rear", CP.tireStiffnessRear) self.active = False - self.calibrated = False - self.calib_from_device = np.eye(3) + self.calibrator = PoseCalibrator() self.speed = 0.0 self.yaw_rate = 0.0 @@ -53,15 +51,12 @@ def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset, P_initial=No def handle_log(self, t, which, msg): if which == 'livePose': - angular_velocity_device = np.array([msg.angularVelocityDevice.x, msg.angularVelocityDevice.y, msg.angularVelocityDevice.z]) - angular_velocity_device_std = np.array([msg.angularVelocityDevice.xStd, msg.angularVelocityDevice.yStd, msg.angularVelocityDevice.zStd]) - angular_velocity_calibrated = np.matmul(self.calib_from_device, angular_velocity_device) - angular_velocity_calibrated_std = rotate_std(self.calib_from_device, angular_velocity_device_std) + device_pose = Pose.from_live_pose(msg) + calibrated_pose = self.calibrator.build_calibrated_pose(device_pose) + self.yaw_rate, self.yaw_rate_std = calibrated_pose.angular_velocity.z, calibrated_pose.angular_velocity.z_std - self.yaw_rate, self.yaw_rate_std = angular_velocity_calibrated[2], angular_velocity_calibrated_std[2] - - localizer_roll = msg.orientationNED.x - localizer_roll_std = np.radians(1) if np.isnan(msg.orientationNED.xStd) else msg.orientationNED.xStd + localizer_roll, localizer_roll_std = device_pose.orientation.x, device_pose.orientation.x_std + localizer_roll_std = np.radians(1) if np.isnan(localizer_roll_std) else localizer_roll_std self.roll_valid = (localizer_roll_std < ROLL_STD_MAX) and (ROLL_MIN < localizer_roll < ROLL_MAX) and msg.sensorsOK if self.roll_valid: roll = localizer_roll @@ -73,7 +68,7 @@ def handle_log(self, t, which, msg): roll_std = np.radians(10.0) self.roll = clip(roll, self.roll - ROLL_MAX_DELTA, self.roll + ROLL_MAX_DELTA) - yaw_rate_valid = msg.angularVelocityDevice.valid and self.calibrated + yaw_rate_valid = msg.angularVelocityDevice.valid and self.calibrator.calib_valid yaw_rate_valid = yaw_rate_valid and 0 < self.yaw_rate_std < 10 # rad/s yaw_rate_valid = yaw_rate_valid and abs(self.yaw_rate) < 1 # rad/s @@ -101,9 +96,7 @@ def handle_log(self, t, which, msg): self.kf.predict_and_observe(t, ObservationKind.STEER_RATIO, np.array([[steer_ratio]])) elif which == 'liveCalibration': - self.calibrated = msg.calStatus == log.LiveCalibrationData.Status.calibrated - device_from_calib = rot_from_euler(np.array(msg.rpyCalib)) - self.calib_from_device = device_from_calib.T + self.calibrator.feed_live_calib(msg) elif which == 'carState': self.steering_angle = msg.steeringAngleDeg @@ -184,7 +177,7 @@ def main(): pInitial = None if DEBUG: - pInitial = np.array(params['filterState']['std']) if 'filterState' in params else None + pInitial = np.array(params['debugFilterState']['std']) if 'debugFilterState' in params else None learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverageDeg']), pInitial) angle_offset_average = params['angleOffsetAverageDeg'] @@ -249,10 +242,9 @@ def main(): liveParameters.angleOffsetAverageStd = float(P[States.ANGLE_OFFSET].item()) liveParameters.angleOffsetFastStd = float(P[States.ANGLE_OFFSET_FAST].item()) if DEBUG: - liveParameters.filterState = log.LiveLocationKalman.Measurement.new_message() - liveParameters.filterState.value = x.tolist() - liveParameters.filterState.std = P.tolist() - liveParameters.filterState.valid = True + liveParameters.debugFilterState = log.LiveParametersData.FilterState.new_message() + liveParameters.debugFilterState.value = x.tolist() + liveParameters.debugFilterState.std = P.tolist() msg.valid = sm.all_checks() diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index edcf42ebcda9a8..2b7cc62527be97 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -8,9 +8,8 @@ from openpilot.common.realtime import config_realtime_process, DT_MDL from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.swaglog import cloudlog -from openpilot.common.transformations.orientation import rot_from_euler from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY -from openpilot.selfdrive.locationd.helpers import PointBuckets, ParameterEstimator +from openpilot.selfdrive.locationd.helpers import PointBuckets, ParameterEstimator, PoseCalibrator, Pose HISTORY = 5 # secs POINTS_PER_BUCKET = 1500 @@ -78,7 +77,7 @@ def __init__(self, CP, decimated=False, track_all_points=False): self.offline_friction = CP.lateralTuning.torque.friction self.offline_latAccelFactor = CP.lateralTuning.torque.latAccelFactor - self.calib_from_device = np.eye(3) + self.calibrator = PoseCalibrator() self.reset() @@ -175,17 +174,17 @@ def handle_log(self, t, which, msg): self.raw_points["vego"].append(msg.vEgo) self.raw_points["steer_override"].append(msg.steeringPressed) elif which == "liveCalibration": - device_from_calib = rot_from_euler(np.array(msg.rpyCalib)) - self.calib_from_device = device_from_calib.T + self.calibrator.feed_live_calib(msg) # calculate lateral accel from past steering torque elif which == "livePose": if len(self.raw_points['steer_torque']) == self.hist_len: - angular_velocity_device = np.array([msg.angularVelocityDevice.x, msg.angularVelocityDevice.y, msg.angularVelocityDevice.z]) - angular_velocity_calibrated = np.matmul(self.calib_from_device, angular_velocity_device) + device_pose = Pose.from_live_pose(msg) + calibrated_pose = self.calibrator.build_calibrated_pose(device_pose) + angular_velocity_calibrated = calibrated_pose.angular_velocity - yaw_rate = angular_velocity_calibrated[2] - roll = msg.orientationNED.x + yaw_rate = angular_velocity_calibrated.yaw + roll = device_pose.orientation.roll # check lat active up to now (without lag compensation) lat_active = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t + self.lag, DT_MDL), self.raw_points['carControl_t'], self.raw_points['lat_active']).astype(bool) diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index f439578afd26ea..86813fcb8ecd66 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -9,6 +9,7 @@ from setproctitle import setproctitle from cereal.messaging import PubMaster, SubMaster from msgq.visionipc import VisionIpcClient, VisionStreamType, VisionBuf +from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.filter_simple import FirstOrderFilter @@ -16,7 +17,7 @@ from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.transformations.model import get_warp_matrix from openpilot.system import sentry -from openpilot.selfdrive.car.car_helpers import get_demo_car_params +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime from openpilot.selfdrive.modeld.parse_model_outputs import Parser @@ -170,7 +171,7 @@ def main(demo=False): if demo: - CP = get_demo_car_params() + CP = convert_to_capnp(get_demo_car_params()) else: CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) diff --git a/selfdrive/modeld/tests/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py index 03c08fd0349e43..1bf2977a919703 100644 --- a/selfdrive/modeld/tests/test_modeld.py +++ b/selfdrive/modeld/tests/test_modeld.py @@ -3,10 +3,11 @@ import cereal.messaging as messaging from msgq.visionipc import VisionIpcServer, VisionStreamType +from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.params import Params from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.realtime import DT_MDL -from openpilot.selfdrive.car.car_helpers import get_demo_car_params +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state @@ -23,7 +24,7 @@ def setup_method(self): self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, CAM.width, CAM.height) self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, CAM.width, CAM.height) self.vipc_server.start_listener() - Params().put("CarParams", get_demo_car_params().to_bytes()) + Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) self.sm = messaging.SubMaster(['modelV2', 'cameraOdometry']) self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'liveCalibration']) diff --git a/selfdrive/modeld/tests/tf_test/build.sh b/selfdrive/modeld/tests/tf_test/build.sh index 4e92ca06981999..df1d24761e9b07 100755 --- a/selfdrive/modeld/tests/tf_test/build.sh +++ b/selfdrive/modeld/tests/tf_test/build.sh @@ -1,2 +1,2 @@ -#!/bin/bash +#!/usr/bin/env bash clang++ -I /home/batman/one/external/tensorflow/include/ -L /home/batman/one/external/tensorflow/lib -Wl,-rpath=/home/batman/one/external/tensorflow/lib main.cc -ltensorflow diff --git a/selfdrive/pandad/tests/test_pandad_loopback.py b/selfdrive/pandad/tests/test_pandad_loopback.py index 3f0926662c854a..0f41201ececc0e 100644 --- a/selfdrive/pandad/tests/test_pandad_loopback.py +++ b/selfdrive/pandad/tests/test_pandad_loopback.py @@ -8,11 +8,11 @@ import cereal.messaging as messaging from cereal import car, log +from opendbc.car.can_definitions import CanData from openpilot.common.retry import retry from openpilot.common.params import Params from openpilot.common.timeout import Timeout from openpilot.selfdrive.pandad import can_list_to_can_capnp -from openpilot.selfdrive.car.can_definitions import CanData from openpilot.system.hardware import TICI from openpilot.selfdrive.test.helpers import phone_only, with_processes diff --git a/selfdrive/test/ci_shell.sh b/selfdrive/test/ci_shell.sh index a5ff714b2d3cdd..76f0a9f78c9e05 100755 --- a/selfdrive/test/ci_shell.sh +++ b/selfdrive/test/ci_shell.sh @@ -1,4 +1,5 @@ -#!/bin/bash -e +#!/usr/bin/env bash +set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" OP_ROOT="$DIR/../../" diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index daf7cec32b8e75..a1eedc915b7ec0 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -47,8 +47,8 @@ def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0, time.sleep(0.1) self.sm = messaging.SubMaster(['longitudinalPlan']) - from openpilot.selfdrive.car.honda.values import CAR - from openpilot.selfdrive.car.honda.interface import CarInterface + from opendbc.car.honda.values import CAR + from opendbc.car.honda.interface import CarInterface self.planner = LongitudinalPlanner(CarInterface.get_non_essential_params(CAR.HONDA_CIVIC), init_v=self.speed) diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 0715fcf7b43f1e..52ed82a7cc0524 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -1,9 +1,9 @@ from collections import defaultdict from cereal import messaging -from openpilot.selfdrive.car.fingerprints import MIGRATION +from opendbc.car.fingerprints import MIGRATION +from opendbc.car.toyota.values import EPS_SCALE from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index -from openpilot.selfdrive.car.toyota.values import EPS_SCALE from openpilot.system.manager.process_config import managed_processes from panda import Panda diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 8cf7d4138a5566..da0197b256c0ad 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -17,13 +17,14 @@ from cereal import car from cereal.services import SERVICE_LIST from msgq.visionipc import VisionIpcServer, get_endpoint_name as vipc_get_endpoint_name +from opendbc.car import structs +from opendbc.car.car_helpers import get_car, interfaces from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.timeout import Timeout from openpilot.common.realtime import DT_CTRL from panda.python import ALTERNATIVE_EXPERIENCE -from openpilot.selfdrive.car.card import can_comm_callbacks -from openpilot.selfdrive.car.car_helpers import get_car, interfaces +from openpilot.selfdrive.car.card import can_comm_callbacks, convert_to_capnp from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams from openpilot.selfdrive.test.process_replay.migration import migrate_all @@ -362,14 +363,14 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): cached_params = None if has_cached_cp: with car.CarParams.from_bytes(cached_params_raw) as _cached_params: - cached_params = _cached_params + cached_params = structs.CarParams(carName=_cached_params.carName, carFw=_cached_params.carFw, carVin=_cached_params.carVin) CP = get_car(*can_callbacks, lambda obd: None, Params().get_bool("ExperimentalLongitudinalEnabled"), cached_params=cached_params).CP if not params.get_bool("DisengageOnAccelerator"): CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - params.put("CarParams", CP.to_bytes()) + params.put("CarParams", convert_to_capnp(CP).to_bytes()) def controlsd_rcv_callback(msg, cfg, frame): @@ -465,6 +466,11 @@ def controlsd_config_callback(params, cfg, lr): assert controlsState is not None and initialized, "controlsState never initialized" params.put("ReplayControlsState", controlsState.as_builder().to_bytes()) + ublox = params.get_bool("UbloxAvailable") + sub_keys = ({"gpsLocation", } if ublox else {"gpsLocationExternal", }) + + cfg.pubs = set(cfg.pubs) - sub_keys + def locationd_config_pubsub_callback(params, cfg, lr): ublox = params.get_bool("UbloxAvailable") @@ -478,9 +484,10 @@ def locationd_config_pubsub_callback(params, cfg, lr): proc_name="controlsd", pubs=[ "carState", "deviceState", "pandaStates", "peripheralState", "liveCalibration", "driverMonitoringState", - "longitudinalPlan", "liveLocationKalman", "liveParameters", "radarState", + "longitudinalPlan", "livePose", "liveParameters", "radarState", "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", - "testJoystick", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput" + "testJoystick", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", + "gpsLocationExternal", "gpsLocation", ], subs=["controlsState", "carControl", "onroadEvents"], ignore=["logMonoTime", "controlsState.startMonoTime", "controlsState.cumLagMs"], diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index a85e8919c4aafe..e580430a3693c4 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -6ca7313b9c1337fad1334d9e087cb4984fdce74d \ No newline at end of file +fa4965a27dee4449ad8b255f9f7674d69327b6f7 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_fuzzy.py b/selfdrive/test/process_replay/test_fuzzy.py index c802d9c573d2c8..d9388390398c7e 100644 --- a/selfdrive/test/process_replay/test_fuzzy.py +++ b/selfdrive/test/process_replay/test_fuzzy.py @@ -4,7 +4,7 @@ from parameterized import parameterized from cereal import log -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA +from opendbc.car.toyota.values import CAR as TOYOTA from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator import openpilot.selfdrive.test.process_replay.process_replay as pr diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 84a19aa0a9ee45..fbd23adf89cc06 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -7,8 +7,8 @@ from tqdm import tqdm from typing import Any +from opendbc.car.car_helpers import interface_names from openpilot.common.git import get_commit -from openpilot.selfdrive.car.car_helpers import interface_names from openpilot.tools.lib.openpilotci import get_url, upload_file from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, replay_process, \ @@ -36,7 +36,6 @@ ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.FORD_BRONCO_SPORT_MK1 # Enable when port is tested and dashcamOnly is no longer set - #("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.TESLA_AP2_MODELS #("VOLKSWAGEN2", "3cfdec54aa035f3f|2022-07-19--23-45-10--2"), # VOLKSWAGEN.VOLKSWAGEN_PASSAT_NMS ] @@ -61,7 +60,7 @@ ] # dashcamOnly makes don't need to be tested until a full port is done -excluded_interfaces = ["mock", "tesla"] +excluded_interfaces = ["mock"] BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") diff --git a/selfdrive/test/profiling/profiler.py b/selfdrive/test/profiling/profiler.py index 2cd547171a4ac3..d50b157a37efca 100755 --- a/selfdrive/test/profiling/profiler.py +++ b/selfdrive/test/profiling/profiler.py @@ -5,13 +5,13 @@ import pprofile import pyprof2calltree +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.volkswagen.values import CAR as VW from openpilot.common.params import Params from openpilot.tools.lib.logreader import LogReader from openpilot.selfdrive.test.profiling.lib import SubMaster, PubMaster, SubSocket, ReplayDone from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.volkswagen.values import CAR as VW BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" diff --git a/selfdrive/test/scons_build_test.sh b/selfdrive/test/scons_build_test.sh index a3b33f797a852c..efc9469deb1fe0 100755 --- a/selfdrive/test/scons_build_test.sh +++ b/selfdrive/test/scons_build_test.sh @@ -1,10 +1,10 @@ -#!/bin/bash +#!/usr/bin/env bash SCRIPT_DIR=$(dirname "$0") BASEDIR=$(realpath "$SCRIPT_DIR/../../") cd $BASEDIR -# tests that our build system's dependencies are configured properly, +# tests that our build system's dependencies are configured properly, # needs a machine with lots of cores scons --clean -scons --no-cache --random -j$(nproc) \ No newline at end of file +scons --no-cache --random -j$(nproc) diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 84dae25821e2a4..fdc222e7e7918c 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e @@ -23,7 +23,7 @@ rm -rf /data/safe_staging/* || true CONTINUE_PATH="/data/continue.sh" tee $CONTINUE_PATH << EOF -#!/usr/bin/bash +#!/usr/bin/env bash sudo abctl --set_success diff --git a/selfdrive/test/setup_vsound.sh b/selfdrive/test/setup_vsound.sh index a6601d0a61d0ac..aab14997448b4a 100755 --- a/selfdrive/test/setup_vsound.sh +++ b/selfdrive/test/setup_vsound.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash { #start pulseaudio daemon diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 5f9e72585203c7..61b0e28483d984 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -36,7 +36,7 @@ PROCS = { # Baseline CPU usage by process "selfdrive.controls.controlsd": 32.0, - "selfdrive.car.card": 22.0, + "selfdrive.car.card": 26.0, "./loggerd": 14.0, "./encoderd": 17.0, "./camerad": 14.5, diff --git a/selfdrive/ui/installer/continue_openpilot.sh b/selfdrive/ui/installer/continue_openpilot.sh index 3da67313eb949c..ed41ab6f3fd16f 100755 --- a/selfdrive/ui/installer/continue_openpilot.sh +++ b/selfdrive/ui/installer/continue_openpilot.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash cd /data/openpilot exec ./launch_openpilot.sh diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 75b966c9aaf757..52d618ab488a9d 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -102,8 +102,6 @@ void Sidebar::updateState(const UIState &s) { ItemStatus pandaStatus = {{tr("VEHICLE"), tr("ONLINE")}, good_color}; if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { pandaStatus = {{tr("NO"), tr("PANDA")}, danger_color}; - } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { - pandaStatus = {{tr("GPS"), tr("SEARCH")}, warning_color}; } setProperty("pandaStatus", QVariant::fromValue(pandaStatus)); } diff --git a/selfdrive/ui/tests/create_test_translations.sh b/selfdrive/ui/tests/create_test_translations.sh index 451a3cbfb04c10..ed0890d94651d4 100755 --- a/selfdrive/ui/tests/create_test_translations.sh +++ b/selfdrive/ui/tests/create_test_translations.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 0b1d8424999c5a..6286517ee6f1f0 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -13,7 +13,6 @@ from msgq.visionipc import VisionIpcServer, VisionStreamType from cereal.messaging import SubMaster, PubMaster -from openpilot.common.mock import mock_messages from openpilot.common.params import Params from openpilot.common.realtime import DT_MDL from openpilot.common.transformations.camera import DEVICE_CAMERAS @@ -92,16 +91,8 @@ def setup_onroad(click, pm: PubMaster): pm.send(msg.which(), msg) server.send(cam_meta.stream, IMG_BYTES, cs.frameId, cs.timestampSof, cs.timestampEof) -@mock_messages(['liveLocationKalman']) -def setup_onroad_map(click, pm: PubMaster): - setup_onroad(click, pm) - - click(500, 500) - - time.sleep(UI_DELAY) # give time for the map to render - def setup_onroad_sidebar(click, pm: PubMaster): - setup_onroad_map(click, pm) + setup_onroad(click, pm) click(500, 500) CASES = { @@ -109,7 +100,6 @@ def setup_onroad_sidebar(click, pm: PubMaster): "settings_device": setup_settings_device, "settings_network": setup_settings_network, "onroad": setup_onroad, - "onroad_map": setup_onroad_map, "onroad_sidebar": setup_onroad_sidebar } @@ -126,7 +116,7 @@ def __init__(self): def setup(self): self.sm = SubMaster(["uiDebug"]) - self.pm = PubMaster(["deviceState", "pandaStates", "controlsState", 'roadCameraState', 'wideRoadCameraState', 'liveLocationKalman']) + self.pm = PubMaster(["deviceState", "pandaStates", "controlsState", 'roadCameraState', 'wideRoadCameraState']) while not self.sm.valid["uiDebug"]: self.sm.update(1) time.sleep(UI_DELAY) # wait a bit more for the UI to start rendering diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index a8a1f29d233e1b..645a63a49378b9 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -779,14 +779,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - بحث - -- -- diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 0b2b794ac4e913..48180eef929944 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -762,14 +762,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - SUCHEN - -- -- diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index c8093e3029dc21..150c00d117a773 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -763,14 +763,6 @@ Esto puede tardar un minuto. PANDA PANDA - - GPS - GPS - - - SEARCH - BÚSQUEDA - -- -- diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index 480d70c481092a..a678742f74b975 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -763,14 +763,6 @@ Cela peut prendre jusqu'à une minute. PANDA PANDA - - GPS - GPS - - - SEARCH - RECHERCHE - -- -- diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index c4481868239acd..096fa9509176ac 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -757,14 +757,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - 検索 - -- -- diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 40d07d9b1c6c42..df012d3e8586ba 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -759,14 +759,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - 검색중 - -- -- diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index c0c7fcb3e83df0..1500f07e63709a 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -763,14 +763,6 @@ Isso pode levar até um minuto. PANDA PANDA - - GPS - GPS - - - SEARCH - PROCURA - -- -- diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 1d7aa3df00541f..bae326d5324efa 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -759,14 +759,6 @@ This may take up to a minute. PANDA PANDA - - GPS - จีพีเอส - - - SEARCH - ค้นหา - -- -- diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index 3fabd5a384cb9c..72148807d430d8 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -757,14 +757,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - ARA - -- -- diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 255886a15e0987..976b58b31d6cd7 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -759,14 +759,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - 搜索中 - -- -- diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 9cea6a1bbc4e50..de8d3ff7018d68 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -759,14 +759,6 @@ This may take up to a minute. PANDA 車輛通訊 - - GPS - GPS - - - SEARCH - 車輛通訊 - -- -- diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index bd26741193b625..6de0babc7b9104 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -242,7 +242,7 @@ void UIState::updateStatus() { UIState::UIState(QObject *parent) : QObject(parent) { sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", - "pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2", + "pandaStates", "carParams", "driverMonitoringState", "carState", "driverStateV2", "wideRoadCameraState", "managerState", "clocks", }); diff --git a/system/hardware/tici/restart_modem.sh b/system/hardware/tici/restart_modem.sh index 3c67d9d21d7dc7..741dc72050fe32 100755 --- a/system/hardware/tici/restart_modem.sh +++ b/system/hardware/tici/restart_modem.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash #nmcli connection modify --temporary lte gsm.home-only yes #nmcli connection modify --temporary lte gsm.auto-config yes diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index aa297269d10c0a..eb3a515b76eeaa 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -7,9 +7,10 @@ import cereal.messaging as messaging from cereal.services import SERVICE_LIST +from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.mock import mock_messages from openpilot.common.params import Params -from openpilot.selfdrive.car.car_helpers import get_demo_car_params +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.hardware.tici.power_monitor import get_power from openpilot.system.manager.process_config import managed_processes from openpilot.system.manager.manager import manager_cleanup @@ -42,7 +43,7 @@ def name(self): class TestPowerDraw: def setup_method(self): - Params().put("CarParams", get_demo_car_params().to_bytes()) + Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) # wait a bit for power save to disable time.sleep(5) @@ -95,7 +96,7 @@ def get_power_with_warmup_for_target(self, proc, prev): return now, msg_counts, time.monotonic() - start_time - SAMPLE_TIME - @mock_messages(['liveLocationKalman']) + @mock_messages(['livePose']) def test_camera_procs(self, subtests): baseline = get_power() diff --git a/tools/cabana/README.md b/tools/cabana/README.md index dbbdd8020ccbf1..27829979c05c93 100644 --- a/tools/cabana/README.md +++ b/tools/cabana/README.md @@ -96,5 +96,3 @@ cabana ## Additional Information For more information, see the [openpilot wiki](https://github.com/commaai/openpilot/wiki/Cabana) - -If you encounter any issues or have feature requests, please contribute bug reports or discussions at: [new cabana feedback](https://github.com/commaai/openpilot/discussions/26091) \ No newline at end of file diff --git a/tools/cabana/dbc/generate_dbc_json.py b/tools/cabana/dbc/generate_dbc_json.py index 2d3fbe9fc47468..04d45f304a64af 100755 --- a/tools/cabana/dbc/generate_dbc_json.py +++ b/tools/cabana/dbc/generate_dbc_json.py @@ -2,8 +2,8 @@ import argparse import json -from openpilot.selfdrive.car.fingerprints import MIGRATION -from openpilot.selfdrive.car.values import PLATFORMS +from opendbc.car.fingerprints import MIGRATION +from opendbc.car.values import PLATFORMS def generate_dbc_json() -> str: diff --git a/tools/cabana/streams/replaystream.cc b/tools/cabana/streams/replaystream.cc index 1616f2aec3ef9c..293b363532f29c 100644 --- a/tools/cabana/streams/replaystream.cc +++ b/tools/cabana/streams/replaystream.cc @@ -63,7 +63,7 @@ bool ReplayStream::loadRoute(const QString &route, const QString &data_dir, uint QString message; if (auth_content.empty()) { message = "Authentication Required. Please run the following command to authenticate:\n\n" - "python tools/lib/auth.py\n\n" + "python3 tools/lib/auth.py\n\n" "This will grant access to routes from your comma account."; } else { message = tr("Access Denied. You do not have permission to access route:\n\n%1\n\n" diff --git a/tools/camerastream/README.md b/tools/camerastream/README.md index 76133f07cde963..7dbafb4be5f8b4 100644 --- a/tools/camerastream/README.md +++ b/tools/camerastream/README.md @@ -1,10 +1,10 @@ # Camera stream -`compressed_vipc.py` connects to a remote device running openpilot, decodes the video streams, and republishes them over VisionIPC. +`compressed_vipc.py` connects to a remote device running openpilot, decodes the video streams, and republishes them over VisionIPC. ## Usage -### On the device +### On the device SSH into the device and run following in separate terminals: `cd /data/openpilot/cereal/messaging && ./bridge` @@ -30,7 +30,7 @@ Alternatively paste this as a single command: wait ) ; trap 'kill $(jobs -p)' SIGINT ``` -Ctrl+C will stop all three processes. +Ctrl+C will stop all three processes. ### On the PC Decode the stream with `compressed_vipc.py`: @@ -43,7 +43,7 @@ To actually display the stream, run `watch3` in separate terminal: ## compressed_vipc.py usage ``` -$ python compressed_vipc.py -h +$ python3 compressed_vipc.py -h usage: compressed_vipc.py [-h] [--nvidia] [--cams CAMS] [--silent] addr Decode video streams and broadcast on VisionIPC diff --git a/tools/car_porting/README.md b/tools/car_porting/README.md index a32e9f96c98d5d..68b0a57fb37039 100644 --- a/tools/car_porting/README.md +++ b/tools/car_porting/README.md @@ -21,7 +21,7 @@ Given a route and platform, automatically inserts FW fingerprints from the platf Example: ```bash -> python tools/car_porting/auto_fingerprint.py '1bbe6bf2d62f58a8|2022-07-14--17-11-43' 'OUTBACK' +> python3 tools/car_porting/auto_fingerprint.py '1bbe6bf2d62f58a8|2022-07-14--17-11-43' 'OUTBACK' Attempting to add fw version for: OUTBACK ``` @@ -45,7 +45,7 @@ Given a route, runs most of the car interface to check for common errors like mi #### Example: panda safety mismatch for gasPressed ```bash -> python tools/car_porting/test_car_model.py '4822a427b188122a|2023-08-14--16-22-21' +> python3 tools/car_porting/test_car_model.py '4822a427b188122a|2023-08-14--16-22-21' ===================================================================== FAIL: test_panda_safety_carstate (__main__.CarModelTestCase.test_panda_safety_carstate) @@ -93,4 +93,4 @@ vin: 1FM5K8GC7NGXXXXXX real platform: FORD EXPLORER 6TH GEN determi vin: 5LM5J7XC8MGXXXXXX real platform: FORD EXPLORER 6TH GEN determined platform: mock correct: False vin: 3FTTW8E31PRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False vin: 3FTTW8E99NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False -``` \ No newline at end of file +``` diff --git a/tools/car_porting/auto_fingerprint.py b/tools/car_porting/auto_fingerprint.py index 145f38c63fceac..5080293e29ebcc 100755 --- a/tools/car_porting/auto_fingerprint.py +++ b/tools/car_porting/auto_fingerprint.py @@ -4,8 +4,8 @@ from collections import defaultdict from openpilot.selfdrive.debug.format_fingerprints import format_brand_fw_versions -from openpilot.selfdrive.car.fingerprints import MIGRATION -from openpilot.selfdrive.car.fw_versions import MODEL_TO_BRAND, match_fw_to_car +from opendbc.car.fingerprints import MIGRATION +from opendbc.car.fw_versions import MODEL_TO_BRAND, match_fw_to_car from openpilot.tools.lib.logreader import LogReader, ReadMode if __name__ == "__main__": diff --git a/tools/install_python_dependencies.sh b/tools/install_python_dependencies.sh index 2783f7282a2a7d..8621ee0b004c2d 100755 --- a/tools/install_python_dependencies.sh +++ b/tools/install_python_dependencies.sh @@ -32,14 +32,10 @@ fi echo "updating uv..." update_uv -# TODO: remove --no-cache once this is fixed: https://github.com/astral-sh/uv/issues/4378 echo "installing python packages..." -uv --no-cache sync --frozen --all-extras +uv sync --frozen --all-extras source .venv/bin/activate -# TODO: remove this. Workaround till get a new release. PEP508 doesn't seem to have find-links option -uv pip install --pre -f https://build.rerun.io/commit/a93faab/wheels --upgrade rerun-sdk - echo "PYTHONPATH=${PWD}" > $ROOT/.env if [[ "$(uname)" == 'Darwin' ]]; then echo "# msgq doesn't work on mac" >> $ROOT/.env diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 176ff25be67a9b..6b85be877760eb 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import os import argparse import threading diff --git a/tools/latencylogger/README.md b/tools/latencylogger/README.md index 421a6a0b4a7018..24169dfaefe3f9 100644 --- a/tools/latencylogger/README.md +++ b/tools/latencylogger/README.md @@ -5,7 +5,7 @@ LatencyLogger is a tool to track the time from first pixel to actuation. Timesta ## Usage ``` -$ python latency_logger.py -h +$ python3 latency_logger.py -h usage: latency_logger.py [-h] [--relative] [--demo] [--plot] [route_or_segment_name] A tool for analyzing openpilot's end-to-end latency diff --git a/tools/lib/comma_car_segments.py b/tools/lib/comma_car_segments.py index 78825504e684d5..fe9c350a9b82c2 100644 --- a/tools/lib/comma_car_segments.py +++ b/tools/lib/comma_car_segments.py @@ -8,7 +8,7 @@ COMMA_CAR_SEGMENTS_LFS_INSTANCE = os.environ.get("COMMA_CAR_SEGMENTS_LFS_INSTANCE", COMMA_CAR_SEGMENTS_REPO) def get_comma_car_segments_database(): - from openpilot.selfdrive.car.fingerprints import MIGRATION + from opendbc.car.fingerprints import MIGRATION database = requests.get(get_repo_raw_url("database.json")).json() diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index 3bfdc75febc772..963d7a8cdb6e10 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -7,10 +7,10 @@ DATA_ENDPOINT = os.getenv("DATA_ENDPOINT", "http://data-raw.comma.internal/") -def internal_source_available(): +def internal_source_available(url=DATA_ENDPOINT): try: - hostname = urlparse(DATA_ENDPOINT).hostname - port = urlparse(DATA_ENDPOINT).port or 80 + hostname = urlparse(url).hostname + port = urlparse(url).port or 80 with socket.socket(socket.AF_INET,socket.SOCK_STREAM) as s: s.connect((hostname, port)) return True diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index 4451d02aeaf001..3881ee7d18bc59 100755 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import termios import atexit diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 2487cb28251a4a..815bd4b796eb94 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -174,6 +174,12 @@ def comma_car_segments_source(sr: SegmentRange, mode=ReadMode.RLOG) -> LogPaths: return [get_comma_segments_url(sr.route_name, seg) for seg in sr.seg_idxs] +def testing_closet_source(sr: SegmentRange, mode=ReadMode.RLOG) -> LogPaths: + if not internal_source_available('http://testing.comma.life'): + raise InternalUnavailableException + return [f"http://testing.comma.life/download/{sr.route_name.replace('|', '/')}/{seg}/rlog" for seg in sr.seg_idxs] + + def direct_source(file_or_url: str) -> LogPaths: return [file_or_url] @@ -195,7 +201,7 @@ def auto_source(sr: SegmentRange, mode=ReadMode.RLOG) -> LogPaths: if mode == ReadMode.SANITIZED: return comma_car_segments_source(sr, mode) - SOURCES: list[Source] = [internal_source, internal_source_zst, openpilotci_source, comma_api_source, comma_car_segments_source,] + SOURCES: list[Source] = [internal_source, internal_source_zst, openpilotci_source, comma_api_source, comma_car_segments_source, testing_closet_source,] exceptions = {} # for automatic fallback modes, auto_source needs to first check if rlogs exist for any source diff --git a/tools/lib/tests/test_comma_car_segments.py b/tools/lib/tests/test_comma_car_segments.py index b9a4def75fb5bf..1b0f07ee63147c 100644 --- a/tools/lib/tests/test_comma_car_segments.py +++ b/tools/lib/tests/test_comma_car_segments.py @@ -1,6 +1,6 @@ import pytest import requests -from openpilot.selfdrive.car.fingerprints import MIGRATION +from opendbc.car.fingerprints import MIGRATION from openpilot.tools.lib.comma_car_segments import get_comma_car_segments_database, get_url from openpilot.tools.lib.logreader import LogReader from openpilot.tools.lib.route import SegmentRange diff --git a/tools/op.sh b/tools/op.sh index a133cc4348f1e9..05a55cd35bdf55 100755 --- a/tools/op.sh +++ b/tools/op.sh @@ -23,7 +23,7 @@ function op_install() { echo "Installing op system-wide..." CMD="\nalias op='"$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )/op.sh" \"\$@\"'\n" grep "alias op=" "$RC_FILE" &> /dev/null || printf "$CMD" >> $RC_FILE - echo -e " ↳ [${GREEN}✔${NC}] op installed successfully. Open a new shell to use it.\n" + echo -e " ↳ [${GREEN}✔${NC}] op installed successfully. Open a new shell to use it." } function loge() { @@ -37,7 +37,13 @@ function loge() { function op_run_command() { CMD="$@" - echo -e "${BOLD}Running:${NC} $CMD" + + echo -e "${BOLD}Running command →${NC} $CMD │" + for ((i=0; i<$((19 + ${#CMD})); i++)); do + echo -n "─" + done + echo -e "┘\n" + if [[ -z "$DRY" ]]; then eval "$CMD" fi @@ -58,7 +64,7 @@ function op_get_openpilot_dir() { function op_check_openpilot_dir() { echo "Checking for openpilot directory..." if [[ -f "$OPENPILOT_ROOT/launch_openpilot.sh" ]]; then - echo -e " ↳ [${GREEN}✔${NC}] openpilot found.\n" + echo -e " ↳ [${GREEN}✔${NC}] openpilot found." return 0 fi @@ -118,7 +124,7 @@ function op_check_os() { fi elif [[ "$OSTYPE" == "darwin"* ]]; then - echo -e " ↳ [${GREEN}✔${NC}] macOS detected.\n" + echo -e " ↳ [${GREEN}✔${NC}] macOS detected." else echo -e " ↳ [${RED}✗${NC}] OS type $OSTYPE not supported!" loge "ERROR_UNKNOWN_OS" "$OSTYPE" @@ -171,7 +177,7 @@ function op_before_cmd() { result="${result}\n$(( op_check_python ) 2>&1)" || (echo -e "$result" && return 1) if [[ -z $VERBOSE ]]; then - echo -e "Checking system → [${GREEN}✔${NC}] system is good." + echo -e "${BOLD}Checking system →${NC} [${GREEN}✔${NC}]" else echo -e "$result" fi @@ -183,7 +189,6 @@ function op_setup() { op_check_openpilot_dir op_check_os - op_check_python echo "Installing dependencies..." st="$(date +%s)" @@ -192,33 +197,33 @@ function op_setup() { elif [[ "$OSTYPE" == "darwin"* ]]; then SETUP_SCRIPT="tools/mac_setup.sh" fi - if ! op_run_command "$OPENPILOT_ROOT/$SETUP_SCRIPT"; then + if ! $OPENPILOT_ROOT/$SETUP_SCRIPT; then echo -e " ↳ [${RED}✗${NC}] Dependencies installation failed!" loge "ERROR_DEPENDENCIES_INSTALLATION" return 1 fi et="$(date +%s)" - echo -e " ↳ [${GREEN}✔${NC}] Dependencies installed successfully in $((et - st)) seconds.\n" + echo -e " ↳ [${GREEN}✔${NC}] Dependencies installed successfully in $((et - st)) seconds." echo "Getting git submodules..." st="$(date +%s)" - if ! op_run_command git submodule update --filter=blob:none --jobs 4 --init --recursive; then + if ! git submodule update --filter=blob:none --jobs 4 --init --recursive; then echo -e " ↳ [${RED}✗${NC}] Getting git submodules failed!" loge "ERROR_GIT_SUBMODULES" return 1 fi et="$(date +%s)" - echo -e " ↳ [${GREEN}✔${NC}] Submodules installed successfully in $((et - st)) seconds.\n" + echo -e " ↳ [${GREEN}✔${NC}] Submodules installed successfully in $((et - st)) seconds." echo "Pulling git lfs files..." st="$(date +%s)" - if ! op_run_command git lfs pull; then + if ! git lfs pull; then echo -e " ↳ [${RED}✗${NC}] Pulling git lfs files failed!" loge "ERROR_GIT_LFS" return 1 fi et="$(date +%s)" - echo -e " ↳ [${GREEN}✔${NC}] Files pulled successfully in $((et - st)) seconds.\n" + echo -e " ↳ [${GREEN}✔${NC}] Files pulled successfully in $((et - st)) seconds." op_check } @@ -268,7 +273,7 @@ function op_juggle() { function op_lint() { op_before_cmd - op_run_command scripts/lint.sh $@ + op_run_command scripts/lint/lint.sh $@ } function op_test() { @@ -307,19 +312,22 @@ function op_default() { echo "" echo -e "${BOLD}${UNDERLINE}Usage:${NC} op [OPTIONS] " echo "" - echo -e "${BOLD}${UNDERLINE}Commands:${NC}" - echo -e " ${BOLD}venv${NC} Activate the python virtual environment" + echo -e "${BOLD}${UNDERLINE}Commands [System]:${NC}" echo -e " ${BOLD}check${NC} Check the development environment (git, os, python) to start using openpilot" + echo -e " ${BOLD}venv${NC} Activate the python virtual environment" echo -e " ${BOLD}setup${NC} Install openpilot dependencies" echo -e " ${BOLD}build${NC} Run the openpilot build system in the current working directory" - echo -e " ${BOLD}sim${NC} Run openpilot in a simulator" + echo -e " ${BOLD}install${NC} Install the 'op' tool system wide" + echo "" + echo -e "${BOLD}${UNDERLINE}Commands [Tooling]:${NC}" echo -e " ${BOLD}juggle${NC} Run PlotJuggler" echo -e " ${BOLD}replay${NC} Run Replay" echo -e " ${BOLD}cabana${NC} Run Cabana" + echo "" + echo -e "${BOLD}${UNDERLINE}Commands [Testing]:${NC}" + echo -e " ${BOLD}sim${NC} Run openpilot in a simulator" echo -e " ${BOLD}lint${NC} Run the linter" echo -e " ${BOLD}test${NC} Run all unit tests from pytest" - echo -e " ${BOLD}help${NC} Show this message" - echo -e " ${BOLD}install${NC} Install the 'op' tool system wide" echo "" echo -e "${BOLD}${UNDERLINE}Options:${NC}" echo -e " ${BOLD}-d, --dir${NC}" @@ -328,8 +336,6 @@ function op_default() { echo " Don't actually run anything, just print what would be run" echo -e " ${BOLD}-n, --no-verify${NC}" echo " Skip environment check before running commands" - echo -e " ${BOLD}-v, --verbose${NC}" - echo " Show the result of all checks before running a command" echo "" echo -e "${BOLD}${UNDERLINE}Examples:${NC}" echo " op setup" @@ -350,7 +356,6 @@ function _op() { -d | --dir ) shift 1; OPENPILOT_ROOT="$1"; shift 1 ;; --dry ) shift 1; DRY="1" ;; -n | --no-verify ) shift 1; NO_VERIFY="1" ;; - -v | --verbose ) shift 1; VERBOSE="1" ;; -l | --log ) shift 1; LOG_FILE="$1" ; shift 1 ;; esac diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index 22854b368d908b..82bd36622f87d8 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -10,8 +10,8 @@ import argparse from functools import partial +from opendbc.car.fingerprints import MIGRATION from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car.fingerprints import MIGRATION from openpilot.tools.lib.logreader import LogReader, ReadMode, save_log juggle_dir = os.path.dirname(os.path.realpath(__file__)) @@ -83,7 +83,7 @@ def juggle_route(route_or_segment_name, can, layout, dbc=None): if dbc is None: for cp in [m for m in all_data if m.which() == 'carParams']: try: - DBC = __import__(f"openpilot.selfdrive.car.{cp.carParams.carName}.values", fromlist=['DBC']).DBC + DBC = __import__(f"opendbc.car.{cp.carParams.carName}.values", fromlist=['DBC']).DBC fingerprint = cp.carParams.carFingerprint dbc = DBC[MIGRATION.get(fingerprint, fingerprint)]['pt'] except Exception: diff --git a/tools/profiling/clpeak/build.sh b/tools/profiling/clpeak/build.sh index 1dcb05cbbc8508..5206ed0c45a71b 100755 --- a/tools/profiling/clpeak/build.sh +++ b/tools/profiling/clpeak/build.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" cd $DIR diff --git a/tools/profiling/ftrace.sh b/tools/profiling/ftrace.sh index fe91a3c0d905b1..7d5d1f5f9d6114 100755 --- a/tools/profiling/ftrace.sh +++ b/tools/profiling/ftrace.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e cd /sys/kernel/tracing diff --git a/tools/profiling/palanteer/setup.sh b/tools/profiling/palanteer/setup.sh index e912a9367fa234..6f115dc86bd53b 100755 --- a/tools/profiling/palanteer/setup.sh +++ b/tools/profiling/palanteer/setup.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e diff --git a/tools/profiling/perfetto/build.sh b/tools/profiling/perfetto/build.sh index 448c1d04aeb856..24255ac3b08392 100755 --- a/tools/profiling/perfetto/build.sh +++ b/tools/profiling/perfetto/build.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash if [ ! -d perfetto ]; then git clone https://android.googlesource.com/platform/external/perfetto/ diff --git a/tools/profiling/perfetto/copy.sh b/tools/profiling/perfetto/copy.sh index 8deca9a6e73910..b91d49a80b65a8 100755 --- a/tools/profiling/perfetto/copy.sh +++ b/tools/profiling/perfetto/copy.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash DEST=tici:/data/openpilot/selfdrive/debug/profiling/perfetto diff --git a/tools/profiling/perfetto/record.sh b/tools/profiling/perfetto/record.sh index 99f2168771cc88..9715a7e7e97cc0 100755 --- a/tools/profiling/perfetto/record.sh +++ b/tools/profiling/perfetto/record.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" cd $DIR diff --git a/tools/profiling/perfetto/server.sh b/tools/profiling/perfetto/server.sh index 19958c653bb761..103ad9bd848db0 100755 --- a/tools/profiling/perfetto/server.sh +++ b/tools/profiling/perfetto/server.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash curl -LO https://get.perfetto.dev/trace_processor chmod +x ./trace_processor diff --git a/tools/profiling/perfetto/traces.sh b/tools/profiling/perfetto/traces.sh index 489b042377c33c..17ca89da72bc3e 100755 --- a/tools/profiling/perfetto/traces.sh +++ b/tools/profiling/perfetto/traces.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash DEST=tici:/data/openpilot/selfdrive/debug/profiling/perfetto diff --git a/tools/profiling/snapdragon/setup-agnos.sh b/tools/profiling/snapdragon/setup-agnos.sh index f036ca211172ef..9a781bf3ce995e 100755 --- a/tools/profiling/snapdragon/setup-agnos.sh +++ b/tools/profiling/snapdragon/setup-agnos.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # TODO: there's probably a better way to do this diff --git a/tools/profiling/snapdragon/setup-profiler.sh b/tools/profiling/snapdragon/setup-profiler.sh index aaec1bf756b8c3..b97c1ae688c074 100755 --- a/tools/profiling/snapdragon/setup-profiler.sh +++ b/tools/profiling/snapdragon/setup-profiler.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # install depends sudo apt update @@ -11,4 +11,4 @@ echo "deb https://download.mono-project.com/repo/ubuntu stable-xenial main" | su sudo apt update sudo apt-get install -y mono-complete -echo "Setup successful, you should now be able to run the profiler with cd SnapdragonProfiler and ./run_sdp.sh" \ No newline at end of file +echo "Setup successful, you should now be able to run the profiler with cd SnapdragonProfiler and ./run_sdp.sh" diff --git a/tools/profiling/watch-irqs.sh b/tools/profiling/watch-irqs.sh index 34cc4596f444cd..4e5cfde3c8bdf8 100755 --- a/tools/profiling/watch-irqs.sh +++ b/tools/profiling/watch-irqs.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e RUBYOPT="-W0" irqtop -d1 -R diff --git a/tools/replay/README.md b/tools/replay/README.md index 122af7152162aa..67cfcd75a61810 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -6,7 +6,7 @@ ```bash # Log in via browser to have access to routes from your comma account -python tools/lib/auth.py +python3 tools/lib/auth.py # Start a replay tools/replay/replay @@ -20,7 +20,7 @@ tools/replay/replay --demo cd selfdrive/ui && ./ui # or try out radar point visualization in Rerun: -python replay/rp_visualization.py +python3 replay/rp_visualization.py # NOTE: To visualize radar points, make sure tools/replay/replay is running. ``` diff --git a/tools/rerun/run.sh b/tools/rerun/run.sh index 25190411d188f7..0c026153603cbc 100755 --- a/tools/rerun/run.sh +++ b/tools/rerun/run.sh @@ -1,4 +1,4 @@ -#! /bin/bash +#!/usr/bin/env bash # TODO: remove this file once Rerun has interface to set log message level set -e diff --git a/tools/scripts/save_ubloxraw_stream.py b/tools/scripts/save_ubloxraw_stream.py index ecbc2bb31ead5c..b5354a7831fb8a 100755 --- a/tools/scripts/save_ubloxraw_stream.py +++ b/tools/scripts/save_ubloxraw_stream.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import argparse import os import sys diff --git a/tools/serial/connect.sh b/tools/serial/connect.sh index a073310b0a8a43..0ea4a73620903d 100755 --- a/tools/serial/connect.sh +++ b/tools/serial/connect.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash while true; do if ls /dev/serial/by-id/usb-FTDI_FT230X* 2> /dev/null; then diff --git a/tools/setup.sh b/tools/setup.sh index 2dc1144900e2be..bc8e41a401f473 100755 --- a/tools/setup.sh +++ b/tools/setup.sh @@ -89,7 +89,7 @@ function ask_dir() { read if [[ ! -z "$REPLY" ]]; then mkdir -p $REPLY - OPENPILOT_ROOT="$(realpath $REPLY/openpilot)" + OPENPILOT_ROOT="$(realpath $REPLY)/openpilot" fi } diff --git a/tools/sim/bridge/common.py b/tools/sim/bridge/common.py index 64407143f7765e..f1d3ef2274c262 100644 --- a/tools/sim/bridge/common.py +++ b/tools/sim/bridge/common.py @@ -7,11 +7,11 @@ from multiprocessing import Process, Queue, Value from abc import ABC, abstractmethod +from opendbc.car.honda.values import CruiseButtons from openpilot.common.params import Params from openpilot.common.numpy_fast import clip from openpilot.common.realtime import Ratekeeper from openpilot.selfdrive.test.helpers import set_params_enabled -from openpilot.selfdrive.car.honda.values import CruiseButtons from openpilot.tools.sim.lib.common import SimulatorState, World from openpilot.tools.sim.lib.simulated_car import SimulatedCar from openpilot.tools.sim.lib.simulated_sensors import SimulatedSensors diff --git a/tools/sim/launch_openpilot.sh b/tools/sim/launch_openpilot.sh index 1b4ac4ef845e50..fa5ac731bd3e8f 100755 --- a/tools/sim/launch_openpilot.sh +++ b/tools/sim/launch_openpilot.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash export PASSIVE="0" export NOBOARD="1" @@ -12,7 +12,7 @@ if [[ "$CI" ]]; then export BLOCK="${BLOCK},ui" fi -python -c "from openpilot.selfdrive.test.helpers import set_params_enabled; set_params_enabled()" +python3 -c "from openpilot.selfdrive.test.helpers import set_params_enabled; set_params_enabled()" SCRIPT_DIR=$(dirname "$0") OPENPILOT_DIR=$SCRIPT_DIR/../../ diff --git a/tools/sim/run_bridge.py b/tools/sim/run_bridge.py index 0992ef4bfe7318..b4da703da0fcbd 100755 --- a/tools/sim/run_bridge.py +++ b/tools/sim/run_bridge.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import argparse from typing import Any diff --git a/tools/webcam/start_camerad.sh b/tools/webcam/start_camerad.sh index fbda2be9f3ca5c..d4828b3e25ce69 100755 --- a/tools/webcam/start_camerad.sh +++ b/tools/webcam/start_camerad.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # export the block below when call manager.py export BLOCK="${BLOCK},camerad" diff --git a/uv.lock b/uv.lock index b5a734f300d9cf..989f40606873ff 100644 --- a/uv.lock +++ b/uv.lock @@ -1,92 +1,98 @@ version = 1 requires-python = ">=3.11" environment-markers = [ - "python_version == '3.11'", - "python_version >= '3.12'", - "python_version < '3.12' and (python_version < '3.11' or python_version > '3.11')", -] - -[[distribution]] + "python_full_version == '3.11.*' and platform_system == 'Darwin'", + "python_full_version == '3.11.*' and platform_machine == 'aarch64' and platform_system == 'Linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_system != 'Darwin') or (python_full_version == '3.11.*' and platform_system != 'Darwin' and platform_system != 'Linux')", + "python_full_version >= '3.12' and platform_system == 'Darwin'", + "python_full_version >= '3.12' and platform_machine == 'aarch64' and platform_system == 'Linux'", + "(python_full_version >= '3.12' and platform_machine != 'aarch64' and platform_system != 'Darwin') or (python_full_version >= '3.12' and platform_system != 'Darwin' and platform_system != 'Linux')", + "python_full_version < '3.11' and platform_system == 'Darwin'", + "python_full_version < '3.11' and platform_machine == 'aarch64' and platform_system == 'Linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_system != 'Darwin') or (python_full_version < '3.11' and platform_system != 'Darwin' and platform_system != 'Linux')", +] + +[[package]] name = "aiohappyeyeballs" -version = "2.3.4" +version = "2.3.5" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3c/c1/52b8ecc87576f8b06fd5132e3ab8550209c958fb450e6d185b15835da82c/aiohappyeyeballs-2.3.4.tar.gz", hash = "sha256:7e1ae8399c320a8adec76f6c919ed5ceae6edd4c3672f4d9eae2b27e37c80ff6", size = 16278 } +sdist = { url = "https://files.pythonhosted.org/packages/b7/c3/112f2f992aeb321de483754c1c5acab08c8ac3388c9c7e6f3e4f45ec1c42/aiohappyeyeballs-2.3.5.tar.gz", hash = "sha256:6fa48b9f1317254f122a07a131a86b71ca6946ca989ce6326fff54a99a920105", size = 16791 } wheels = [ - { url = "https://files.pythonhosted.org/packages/93/fd/a19345071360a94345ebecaa268d6c6f56900687d91ef775fe2496a76100/aiohappyeyeballs-2.3.4-py3-none-any.whl", hash = "sha256:40a16ceffcf1fc9e142fd488123b2e218abc4188cf12ac20c67200e1579baa42", size = 12001 }, + { url = "https://files.pythonhosted.org/packages/8b/b4/0983e94060405eb51f23be493e3f5c28003f7ebc5efcd0803c1cb23ea407/aiohappyeyeballs-2.3.5-py3-none-any.whl", hash = "sha256:4d6dea59215537dbc746e93e779caea8178c866856a721c9c660d7a5a7b8be03", size = 12139 }, ] -[[distribution]] +[[package]] name = "aiohttp" -version = "3.10.1" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "aiohappyeyeballs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "aiosignal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "attrs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "frozenlist", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "multidict", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "yarl", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/f7/e1/bfcafd54dee859b2e6e690c5f8a8a30343d590a8822bb0669afba4c2c9e6/aiohttp-3.10.1.tar.gz", hash = "sha256:8b0d058e4e425d3b45e8ec70d49b402f4d6b21041e674798b1f91ba027c73f28", size = 7517572 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1f/b4/682aefe768cf7799aa38841724d446d532c687afad96fec379f1f2651146/aiohttp-3.10.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f6979b4f20d3e557a867da9d9227de4c156fcdcb348a5848e3e6190fd7feb972", size = 582530 }, - { url = "https://files.pythonhosted.org/packages/cc/dd/11045c0b347e5acd796648adbf02fb1f7d83d07ec5437bb288d3b349e846/aiohttp-3.10.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:03c0c380c83f8a8d4416224aafb88d378376d6f4cadebb56b060688251055cd4", size = 394293 }, - { url = "https://files.pythonhosted.org/packages/b1/59/d14ec2a49dc58ec18f67c92bb111113440a3e0010cb3dd3d9f4f16563609/aiohttp-3.10.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1c2b104e81b3c3deba7e6f5bc1a9a0e9161c380530479970766a6655b8b77c7c", size = 385102 }, - { url = "https://files.pythonhosted.org/packages/9d/f9/8aa14244f9d4a02e7b1239326f3ffd38c212e515ab59d1b3e62d78bb98a1/aiohttp-3.10.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b023b68c61ab0cd48bd38416b421464a62c381e32b9dc7b4bdfa2905807452a4", size = 1317213 }, - { url = "https://files.pythonhosted.org/packages/58/f1/6fe725d90806f22a49e3a4653795b322d89f4596549dfb219d2f1aee28dd/aiohttp-3.10.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1a07c76a82390506ca0eabf57c0540cf5a60c993c442928fe4928472c4c6e5e6", size = 1353971 }, - { url = "https://files.pythonhosted.org/packages/ba/87/bf8e4351f552dd8c70bcf9a33b187de56e198c1f7ec89e46c4553cd7cf2a/aiohttp-3.10.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:41d8dab8c64ded1edf117d2a64f353efa096c52b853ef461aebd49abae979f16", size = 1391301 }, - { url = "https://files.pythonhosted.org/packages/5e/46/5c102cb40305b38c9d7bceee84ca87a6c12e8fae52a2e8375bc55555adb0/aiohttp-3.10.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:615348fab1a9ef7d0960a905e83ad39051ae9cb0d2837da739b5d3a7671e497a", size = 1302114 }, - { url = "https://files.pythonhosted.org/packages/cd/1d/5ac784a10db7dd054240d07538ad463e2d1fad24fbfb32b46f0ac67e6ce2/aiohttp-3.10.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:256ee6044214ee9d66d531bb374f065ee94e60667d6bbeaa25ca111fc3997158", size = 1261793 }, - { url = "https://files.pythonhosted.org/packages/2c/ec/7c15d8d2b7cff7bb705d3b9257184fccb9255425cfb9c66ff52cb8049790/aiohttp-3.10.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b7d5bb926805022508b7ddeaad957f1fce7a8d77532068d7bdb431056dc630cd", size = 1282815 }, - { url = "https://files.pythonhosted.org/packages/e3/37/863dd5d9f265b850a48aa8e45a883d51ed881f044fe21c206e87a07c7abf/aiohttp-3.10.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:028faf71b338f069077af6315ad54281612705d68889f5d914318cbc2aab0d50", size = 1277020 }, - { url = "https://files.pythonhosted.org/packages/19/4c/6fe69dbfc2fc6ae9ca31452c0c756bdf2c71e683c83937b50f41a02bf8df/aiohttp-3.10.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:5c12310d153b27aa630750be44e79313acc4e864c421eb7d2bc6fa3429c41bf8", size = 1330103 }, - { url = "https://files.pythonhosted.org/packages/dd/61/f6bdf4e5ad57de9929f4e4623d088b10345b68cf680e58667c1b97380f79/aiohttp-3.10.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:de1a91d5faded9054957ed0a9e01b9d632109341942fc123947ced358c5d9009", size = 1350433 }, - { url = "https://files.pythonhosted.org/packages/6d/f4/e10165c17a280e8edf68595cbbf22a6f89768e61621e050882d7c0ca533f/aiohttp-3.10.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:9c186b270979fb1dee3ababe2d12fb243ed7da08b30abc83ebac3a928a4ddb15", size = 1309638 }, - { url = "https://files.pythonhosted.org/packages/ef/10/0c63bf328ebbd90453b415fb5d92b1a1a92d6b277e96c55dce600caddfe3/aiohttp-3.10.1-cp311-cp311-win32.whl", hash = "sha256:4a9ce70f5e00380377aac0e568abd075266ff992be2e271765f7b35d228a990c", size = 355786 }, - { url = "https://files.pythonhosted.org/packages/82/81/49afec048067b4436fafdf5d0ac8ce07fb8058ca19cb7a37a15e283397c8/aiohttp-3.10.1-cp311-cp311-win_amd64.whl", hash = "sha256:a77c79bac8d908d839d32c212aef2354d2246eb9deb3e2cb01ffa83fb7a6ea5d", size = 375614 }, - { url = "https://files.pythonhosted.org/packages/b9/35/bc0ad5fdf85ef6d8188cc0c75360c0abb02463c5576ebb99565fb381010d/aiohttp-3.10.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:2212296cdb63b092e295c3e4b4b442e7b7eb41e8a30d0f53c16d5962efed395d", size = 579105 }, - { url = "https://files.pythonhosted.org/packages/e4/2a/f34963d61ad73e01d2b1f60e7100c29d66bab6b3e9f3af5b5e1863c40314/aiohttp-3.10.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:4dcb127ca3eb0a61205818a606393cbb60d93b7afb9accd2fd1e9081cc533144", size = 390785 }, - { url = "https://files.pythonhosted.org/packages/93/17/dff64781014a8595c06d3ec88a3f76d063c61371f81dcc0eb40b1d9399c5/aiohttp-3.10.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:cb8b79a65332e1a426ccb6290ce0409e1dc16b4daac1cc5761e059127fa3d134", size = 385426 }, - { url = "https://files.pythonhosted.org/packages/e4/17/14c37f43cf46ae883185c479e010472636577b7d17fba36daef5ddcdec57/aiohttp-3.10.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:68cc24f707ed9cb961f6ee04020ca01de2c89b2811f3cf3361dc7c96a14bfbcc", size = 1323084 }, - { url = "https://files.pythonhosted.org/packages/8a/da/6486c426dde538b24e3f02a6fd841142a4cd2fd9c9a80e8537db5c36e144/aiohttp-3.10.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9cb54f5725b4b37af12edf6c9e834df59258c82c15a244daa521a065fbb11717", size = 1362741 }, - { url = "https://files.pythonhosted.org/packages/f6/7e/87e0ada9b0a7dea935671c0a33ec1428267efee857f93564aa0e83eb942e/aiohttp-3.10.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:51d03e948e53b3639ce4d438f3d1d8202898ec6655cadcc09ec99229d4adc2a9", size = 1404852 }, - { url = "https://files.pythonhosted.org/packages/22/11/9960494844f900d34693a5d49a9491340e708ed530b5bb2b8bdd4a0136eb/aiohttp-3.10.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:786299d719eb5d868f161aeec56d589396b053925b7e0ce36e983d30d0a3e55c", size = 1318565 }, - { url = "https://files.pythonhosted.org/packages/02/40/d26e1a4af08f092dee09eff33a16562cb43a721251023e7e1cd9fdeb8f0f/aiohttp-3.10.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:abda4009a30d51d3f06f36bc7411a62b3e647fa6cc935ef667e3e3d3a7dd09b1", size = 1270651 }, - { url = "https://files.pythonhosted.org/packages/b8/a8/24a04764c0e7f30c901ff40408941049ee8c496ef9f60ffa51798c776321/aiohttp-3.10.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:67f7639424c313125213954e93a6229d3a1d386855d70c292a12628f600c7150", size = 1285321 }, - { url = "https://files.pythonhosted.org/packages/32/4c/9e0162927eda41006891f0e3e0499dcbb19513f6643291c5742c69d4b5bd/aiohttp-3.10.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:8e5a26d7aac4c0d8414a347da162696eea0629fdce939ada6aedf951abb1d745", size = 1287408 }, - { url = "https://files.pythonhosted.org/packages/9f/62/71ac0a332408f66b6ba31300532987287b85c38a56ef9e3d7fe8247cc81a/aiohttp-3.10.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:120548d89f14b76a041088b582454d89389370632ee12bf39d919cc5c561d1ca", size = 1333511 }, - { url = "https://files.pythonhosted.org/packages/49/85/52e2ac28584b0c140737bd378143d4398a6e2838097764d5e6ffc862d85e/aiohttp-3.10.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:f5293726943bdcea24715b121d8c4ae12581441d22623b0e6ab12d07ce85f9c4", size = 1356616 }, - { url = "https://files.pythonhosted.org/packages/ea/78/3a01012380be75c8c42373ad54fea3cce73e590d2b863e490f709210ca4b/aiohttp-3.10.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1f8605e573ed6c44ec689d94544b2c4bb1390aaa723a8b5a2cc0a5a485987a68", size = 1321986 }, - { url = "https://files.pythonhosted.org/packages/49/4e/7a7c6988884425dfb9d4bbe24e1fab0e7b24bfd6f857c1521b4b5a42f229/aiohttp-3.10.1-cp312-cp312-win32.whl", hash = "sha256:e7168782621be4448d90169a60c8b37e9b0926b3b79b6097bc180c0a8a119e73", size = 353400 }, - { url = "https://files.pythonhosted.org/packages/c0/66/ae547a96abcbed450cabf2d438d9376b852c028838a50ee2c7678e2e5830/aiohttp-3.10.1-cp312-cp312-win_amd64.whl", hash = "sha256:8fbf8c0ded367c5c8eaf585f85ca8dd85ff4d5b73fb8fe1e6ac9e1b5e62e11f7", size = 374114 }, -] - -[[distribution]] +version = "3.10.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "aiohappyeyeballs" }, + { name = "aiosignal" }, + { name = "attrs" }, + { name = "frozenlist" }, + { name = "multidict" }, + { name = "yarl" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/15/9c/ed427fcc46423c965a8e33673d7111b6e3b3aa7d61ca52163a720ff200cb/aiohttp-3.10.3.tar.gz", hash = "sha256:21650e7032cc2d31fc23d353d7123e771354f2a3d5b05a5647fc30fea214e696", size = 7521618 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/8c/e4/2dec0e2eca35a23aeba5861f27c013988354d58ea5eb445b94e07d08113f/aiohttp-3.10.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e021c4c778644e8cdc09487d65564265e6b149896a17d7c0f52e9a088cc44e1b", size = 585893 }, + { url = "https://files.pythonhosted.org/packages/0a/d2/a2ad7940fac1245a1e7fb7c76db298c88b44890991972bf1c1c502c5398c/aiohttp-3.10.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:24fade6dae446b183e2410a8628b80df9b7a42205c6bfc2eff783cbeedc224a2", size = 396679 }, + { url = "https://files.pythonhosted.org/packages/8c/cb/16b5dce7f304d5f099537e681c484f06c904658c344363d2d6278e496717/aiohttp-3.10.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:bc8e9f15939dacb0e1f2d15f9c41b786051c10472c7a926f5771e99b49a5957f", size = 388407 }, + { url = "https://files.pythonhosted.org/packages/62/73/9448de67dd32197ad2be12e2d79e1558cd9a7fb8caa037da1599ff9625f9/aiohttp-3.10.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d5a9ec959b5381271c8ec9310aae1713b2aec29efa32e232e5ef7dcca0df0279", size = 1325574 }, + { url = "https://files.pythonhosted.org/packages/f1/b1/32680f32c30c28c9929e9438451d0c8b310261927a66483141cb3c8c52d7/aiohttp-3.10.3-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:2a5d0ea8a6467b15d53b00c4e8ea8811e47c3cc1bdbc62b1aceb3076403d551f", size = 1363988 }, + { url = "https://files.pythonhosted.org/packages/17/8d/5419529821ca2d82153787f6638b885d55c79da940a19c0eb1dc14aba566/aiohttp-3.10.3-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c9ed607dbbdd0d4d39b597e5bf6b0d40d844dfb0ac6a123ed79042ef08c1f87e", size = 1399346 }, + { url = "https://files.pythonhosted.org/packages/2a/35/9b740478c4d6ddb4756e2a9bf0c4b7936483a9ff92d2e0cad125a261c650/aiohttp-3.10.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d3e66d5b506832e56add66af88c288c1d5ba0c38b535a1a59e436b300b57b23e", size = 1312358 }, + { url = "https://files.pythonhosted.org/packages/3a/6c/868f6c08cfac8374ea11c00199d556d8a65d9dd9ea59bd1c8c519a0b6943/aiohttp-3.10.3-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fda91ad797e4914cca0afa8b6cccd5d2b3569ccc88731be202f6adce39503189", size = 1270752 }, + { url = "https://files.pythonhosted.org/packages/4f/5a/a0ed4b884ad4c5cf4160f32a3a0c0de72b462360c25d1b6107aac1f40a1a/aiohttp-3.10.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:61ccb867b2f2f53df6598eb2a93329b5eee0b00646ee79ea67d68844747a418e", size = 1291095 }, + { url = "https://files.pythonhosted.org/packages/de/9d/b7e2ed758c77cecc0cdc0a59c01d4f5dd4b2354e120bca66537b14a9b67c/aiohttp-3.10.3-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:6d881353264e6156f215b3cb778c9ac3184f5465c2ece5e6fce82e68946868ef", size = 1285734 }, + { url = "https://files.pythonhosted.org/packages/d5/d4/86f36f6297c445121c5df2f4dea6dff00b9df6164ad20073cdb2c1b24e30/aiohttp-3.10.3-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:b031ce229114825f49cec4434fa844ccb5225e266c3e146cb4bdd025a6da52f1", size = 1341295 }, + { url = "https://files.pythonhosted.org/packages/f5/95/f47d9b8d58efe08eb19cab01b51cd016c5c3b94b06b28fabeecdf1a7cee0/aiohttp-3.10.3-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:5337cc742a03f9e3213b097abff8781f79de7190bbfaa987bd2b7ceb5bb0bdec", size = 1361068 }, + { url = "https://files.pythonhosted.org/packages/c5/7b/89714591adf08b5ed30a8f1f587994ee3302c8e696101fe68497bf6e59a2/aiohttp-3.10.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:ab3361159fd3dcd0e48bbe804006d5cfb074b382666e6c064112056eb234f1a9", size = 1320314 }, + { url = "https://files.pythonhosted.org/packages/02/fc/e8ad1937309c9315f8c427bfd0931cee2d87c9fa7dc76ed4ee06165081c4/aiohttp-3.10.3-cp311-cp311-win32.whl", hash = "sha256:05d66203a530209cbe40f102ebaac0b2214aba2a33c075d0bf825987c36f1f0b", size = 358715 }, + { url = "https://files.pythonhosted.org/packages/7d/c2/598addd5ec6f3edcc25c846d0ea22c54f2460e550ea15e470d1b60c2e8d6/aiohttp-3.10.3-cp311-cp311-win_amd64.whl", hash = "sha256:70b4a4984a70a2322b70e088d654528129783ac1ebbf7dd76627b3bd22db2f17", size = 378587 }, + { url = "https://files.pythonhosted.org/packages/20/1f/b893d3fa8249b8a904cf8f6ae202479fd4baa5260379f6463e28796863c1/aiohttp-3.10.3-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:166de65e2e4e63357cfa8417cf952a519ac42f1654cb2d43ed76899e2319b1ee", size = 582908 }, + { url = "https://files.pythonhosted.org/packages/95/73/05647e72370a9b2526c9994ef8a2f2bd6293d397d550c715f8b9fc4dd649/aiohttp-3.10.3-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:7084876352ba3833d5d214e02b32d794e3fd9cf21fdba99cff5acabeb90d9806", size = 393506 }, + { url = "https://files.pythonhosted.org/packages/61/a9/0e03cc539186eb65d6ed74cac4b1f79be22810ee1a4235746143d4889c97/aiohttp-3.10.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8d98c604c93403288591d7d6d7d6cc8a63459168f8846aeffd5b3a7f3b3e5e09", size = 388546 }, + { url = "https://files.pythonhosted.org/packages/47/bc/0b3862e2a13ba44fe29cbf11766c61fe72b738c843401470b9e4c42fa7b2/aiohttp-3.10.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d73b073a25a0bb8bf014345374fe2d0f63681ab5da4c22f9d2025ca3e3ea54fc", size = 1332184 }, + { url = "https://files.pythonhosted.org/packages/90/9d/e38ecbdd41cb62cd3ea2c7e1a5ba2912dc9bf5a446db89474178a5848cd5/aiohttp-3.10.3-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8da6b48c20ce78f5721068f383e0e113dde034e868f1b2f5ee7cb1e95f91db57", size = 1371578 }, + { url = "https://files.pythonhosted.org/packages/2a/ca/1d1432dd48d587b8d92585677687f0a0ade2397ca4890a713ff8ed0af2ca/aiohttp-3.10.3-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3a9dcdccf50284b1b0dc72bc57e5bbd3cc9bf019060dfa0668f63241ccc16aa7", size = 1413858 }, + { url = "https://files.pythonhosted.org/packages/0b/1d/8b50ff7908e7f4ea98bb961e584e53599b268a2898740880d6c43a958db9/aiohttp-3.10.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:56fb94bae2be58f68d000d046172d8b8e6b1b571eb02ceee5535e9633dcd559c", size = 1327549 }, + { url = "https://files.pythonhosted.org/packages/c6/10/62419a47cf394e9f95d5a80245f8e32d6cbcad62e5d3f9660be372827f85/aiohttp-3.10.3-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bf75716377aad2c718cdf66451c5cf02042085d84522aec1f9246d3e4b8641a6", size = 1279573 }, + { url = "https://files.pythonhosted.org/packages/11/3c/174127b1f1ca0d22984f4c2f5701839aa6a722d1b6437a28d6e63d0f0241/aiohttp-3.10.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6c51ed03e19c885c8e91f574e4bbe7381793f56f93229731597e4a499ffef2a5", size = 1292106 }, + { url = "https://files.pythonhosted.org/packages/a2/5f/9f38854806854bdc59f96b94084054e7195aa14d54e8542bff2eeab8b07c/aiohttp-3.10.3-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:b84857b66fa6510a163bb083c1199d1ee091a40163cfcbbd0642495fed096204", size = 1300437 }, + { url = "https://files.pythonhosted.org/packages/a8/d6/53dde1dd45b5018b4e5fa863475ba5c1ad4775f1380db09057ea2aab84b6/aiohttp-3.10.3-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:c124b9206b1befe0491f48185fd30a0dd51b0f4e0e7e43ac1236066215aff272", size = 1338715 }, + { url = "https://files.pythonhosted.org/packages/4d/70/620a2f1af15b4772221b53b4b264dd58ea6b254babe1f8cbe4b33b18d82b/aiohttp-3.10.3-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:3461d9294941937f07bbbaa6227ba799bc71cc3b22c40222568dc1cca5118f68", size = 1366441 }, + { url = "https://files.pythonhosted.org/packages/55/a6/0b7e8fcaea09b9a7ed20393117385e9943452d47387ab41c0f855bc90a2d/aiohttp-3.10.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:08bd0754d257b2db27d6bab208c74601df6f21bfe4cb2ec7b258ba691aac64b3", size = 1328905 }, + { url = "https://files.pythonhosted.org/packages/32/b3/acb4b9d6b8291d897727a21a78c8d2ac9cf66710a401533ea18e22e0578d/aiohttp-3.10.3-cp312-cp312-win32.whl", hash = "sha256:7f9159ae530297f61a00116771e57516f89a3de6ba33f314402e41560872b50a", size = 356415 }, + { url = "https://files.pythonhosted.org/packages/fa/37/df0bffb89398d7788fac30af3578e80d42bd40918d7d9ba897f9577b6b73/aiohttp-3.10.3-cp312-cp312-win_amd64.whl", hash = "sha256:e1128c5d3a466279cb23c4aa32a0f6cb0e7d2961e74e9e421f90e74f75ec1edf", size = 377093 }, +] + +[[package]] name = "aioice" version = "0.9.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "dnspython", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "ifaddr", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "dnspython" }, + { name = "ifaddr" }, ] sdist = { url = "https://files.pythonhosted.org/packages/33/b6/e2b0e48ccb5b04fe29265e93f14a0915f416e359c897ae87d570566c430b/aioice-0.9.0.tar.gz", hash = "sha256:fc2401b1c4b6e19372eaaeaa28fd1bd9cbf6b0e412e48625297c53b495eebd1e", size = 40324 } wheels = [ { url = "https://files.pythonhosted.org/packages/b6/35/d21e48d3ba25d32aba5d142d54c4491376c659dd74d052a30dd25198007b/aioice-0.9.0-py3-none-any.whl", hash = "sha256:b609597a3a5a611e0004ff04772e16aceb881d51c25c0afc4ceac05d5e50024e", size = 24177 }, ] -[[distribution]] +[[package]] name = "aiortc" version = "1.9.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "aioice", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "av", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cffi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cryptography", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "google-crc32c", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyee", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pylibsrtp", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyopenssl", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "aioice" }, + { name = "av" }, + { name = "cffi" }, + { name = "cryptography" }, + { name = "google-crc32c" }, + { name = "pyee" }, + { name = "pylibsrtp" }, + { name = "pyopenssl" }, ] sdist = { url = "https://files.pythonhosted.org/packages/71/32/e9b01e2271124643e5dc15c273f2bb8155efebf5bc2115407441ac62f4c5/aiortc-1.9.0.tar.gz", hash = "sha256:03faa76d76ef0e5989ac10386898b029369756102217230e2fcd4b029c50b303", size = 1168973 } wheels = [ @@ -99,28 +105,28 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/6a/df/de098b31a3fbf1117f6d4cb84c14518636054e3c95a9d9f693a1123c95b3/aiortc-1.9.0-cp38-abi3-win_amd64.whl", hash = "sha256:de5e7020cfc2d2d9fb95690926ff2e3b3c30cd4f5f5bc68d5b6756a8eebb686e", size = 1009610 }, ] -[[distribution]] +[[package]] name = "aiosignal" version = "1.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "frozenlist", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "frozenlist" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ae/67/0952ed97a9793b4958e5736f6d2b346b414a2cd63e82d05940032f45b32f/aiosignal-1.3.1.tar.gz", hash = "sha256:54cd96e15e1649b75d6c87526a6ff0b6c1b0dd3459f43d9ca11d48c339b68cfc", size = 19422 } wheels = [ { url = "https://files.pythonhosted.org/packages/76/ac/a7305707cb852b7e16ff80eaf5692309bde30e2b1100a1fcacdc8f731d97/aiosignal-1.3.1-py3-none-any.whl", hash = "sha256:f8376fb07dd1e86a584e4fcdec80b36b7f81aac666ebc724e2c090300dd83b17", size = 7617 }, ] -[[distribution]] +[[package]] name = "attrs" -version = "24.1.0" +version = "24.2.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/39/31/ca3e2de55503d8ad75985865629f69a2c376a44428c5df1450b749d30751/attrs-24.1.0.tar.gz", hash = "sha256:adbdec84af72d38be7628e353a09b6a6790d15cd71819f6e9d7b0faa8a125745", size = 792572 } +sdist = { url = "https://files.pythonhosted.org/packages/fc/0f/aafca9af9315aee06a89ffde799a10a582fe8de76c563ee80bbcdc08b3fb/attrs-24.2.0.tar.gz", hash = "sha256:5cfb1b9148b5b086569baec03f20d7b6bf3bcacc9a42bebf87ffaaca362f6346", size = 792678 } wheels = [ - { url = "https://files.pythonhosted.org/packages/9b/2b/913eda7a67f7bea7496c1a8e1666f48aa9f15520da79368e4ec1109e2690/attrs-24.1.0-py3-none-any.whl", hash = "sha256:377b47448cb61fea38533f671fba0d0f8a96fd58facd4dc518e3dac9dbea0905", size = 63880 }, + { url = "https://files.pythonhosted.org/packages/6a/21/5b6702a7f963e95456c0de2d495f67bf5fd62840ac655dc451586d23d39a/attrs-24.2.0-py3-none-any.whl", hash = "sha256:81921eb96de3191c8258c199618104dd27ac608d9366f5e35d011eae1867ede2", size = 63001 }, ] -[[distribution]] +[[package]] name = "av" version = "12.3.0" source = { registry = "https://pypi.org/simple" } @@ -140,57 +146,57 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/96/67/9f1c444864d4f3e3773100b9ed20e670f80d5575b7a8fd53cca20de9d681/av-12.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:62d036ee8321d67190887012c3dbcd1ad83248603cc29ea75fbb75835b8d6e6e", size = 25977611 }, ] -[[distribution]] +[[package]] name = "azure-core" version = "1.30.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "requests", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "six", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "requests" }, + { name = "six" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/99/d4/1f469fa246f554b86fb5cebc30eef1b2a38b7af7a2c2791bce0a4c6e4604/azure-core-1.30.2.tar.gz", hash = "sha256:a14dc210efcd608821aa472d9fb8e8d035d29b68993819147bc290a8ac224472", size = 271104 } wheels = [ { url = "https://files.pythonhosted.org/packages/ef/d7/69d53f37733f8cb844862781767aef432ff3152bc9b9864dc98c7e286ce9/azure_core-1.30.2-py3-none-any.whl", hash = "sha256:cf019c1ca832e96274ae85abd3d9f752397194d9fea3b41487290562ac8abe4a", size = 194253 }, ] -[[distribution]] +[[package]] name = "azure-identity" version = "1.17.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "azure-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cryptography", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "msal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "msal-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "azure-core" }, + { name = "cryptography" }, + { name = "msal" }, + { name = "msal-extensions" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/51/c9/f7e3926686a89670ce641b360bd2da9a2d7a12b3e532403462d99f81e9d5/azure-identity-1.17.1.tar.gz", hash = "sha256:32ecc67cc73f4bd0595e4f64b1ca65cd05186f4fe6f98ed2ae9f1aa32646efea", size = 246652 } wheels = [ { url = "https://files.pythonhosted.org/packages/49/83/a777861351e7b99e7c84ff3b36bab35e87b6e5d36e50b6905e148c696515/azure_identity-1.17.1-py3-none-any.whl", hash = "sha256:db8d59c183b680e763722bfe8ebc45930e6c57df510620985939f7f3191e0382", size = 173229 }, ] -[[distribution]] +[[package]] name = "azure-storage-blob" -version = "12.21.0" +version = "12.22.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "azure-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cryptography", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "isodate", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "azure-core" }, + { name = "cryptography" }, + { name = "isodate" }, + { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/97/c9/0e1e864eef8071102de2d6b11dfcf8d35410735145b2fbc2e0a5f58d1490/azure-storage-blob-12.21.0.tar.gz", hash = "sha256:b9722725072f5b7373c0f4dd6d78fbae2bb37bffc5c3e01731ab8c750ee8dd7e", size = 557430 } +sdist = { url = "https://files.pythonhosted.org/packages/92/de/9cea85c0d5fc21f99bcf9f060fc2287cb95236b70431fa63cb69890a121e/azure-storage-blob-12.22.0.tar.gz", hash = "sha256:b3804bb4fe8ab1c32771fa464053da772a682c2737b19da438a3f4e5e3b3736e", size = 564873 } wheels = [ - { url = "https://files.pythonhosted.org/packages/f4/da/4033cee3855395e84ff73da4b50d3528f9338205299cde89676639387fcc/azure_storage_blob-12.21.0-py3-none-any.whl", hash = "sha256:f9ede187dd5a0ef296b583a7c1861c6938ddd6708d6e70f4203a163c2ab42d43", size = 396449 }, + { url = "https://files.pythonhosted.org/packages/a8/52/b578c94048469fbf9f6378e2b2a46a2d0ccba3d59a7845dbed22ebf61601/azure_storage_blob-12.22.0-py3-none-any.whl", hash = "sha256:bb7d2d824ce3f11f14a27ee7d9281289f7e072ac8311c52e3652672455b7d5e8", size = 404892 }, ] -[[distribution]] +[[package]] name = "casadi" version = "3.6.6" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f2/d4/1d54b291225d3ada8bc149726bcb8480a56155430c86a2b03a9210048b3a/casadi-3.6.6.tar.gz", hash = "sha256:104601d37ab7ebf897bce7e097823bb090dd7629a7cc4c2e76780f46fc0e59f6", size = 5130529 } wheels = [ @@ -212,7 +218,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/41/21/dac7073d9d27d3527cf64797f5ae010a7e05e32864ccdf6b461597c323a0/casadi-3.6.6-cp312-none-win_amd64.whl", hash = "sha256:1111aed9afee22c52ba824d60e189a93b8db379d3749ea6d51434c796c7db74f", size = 46199935 }, ] -[[distribution]] +[[package]] name = "certifi" version = "2024.7.4" source = { registry = "https://pypi.org/simple" } @@ -221,39 +227,52 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/1c/d5/c84e1a17bf61d4df64ca866a1c9a913874b4e9bdc131ec689a0ad013fb36/certifi-2024.7.4-py3-none-any.whl", hash = "sha256:c198e21b1289c2ab85ee4e67bb4b4ef3ead0892059901a8d5b622f24a1101e90", size = 162960 }, ] -[[distribution]] +[[package]] name = "cffi" -version = "1.16.0" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "pycparser", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/68/ce/95b0bae7968c65473e1298efb042e10cafc7bafc14d9e4f154008241c91d/cffi-1.16.0.tar.gz", hash = "sha256:bcb3ef43e58665bbda2fb198698fcae6776483e0c4a631aa5647806c25e02cc0", size = 512873 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/95/c8/ce05a6cba2bec12d4b28285e66c53cc88dd7385b102dea7231da3b74cfef/cffi-1.16.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b84834d0cf97e7d27dd5b7f3aca7b6e9263c56308ab9dc8aae9784abb774d404", size = 182415 }, - { url = "https://files.pythonhosted.org/packages/18/6c/0406611f3d5aadf4c5b08f6c095d874aed8dfc2d3a19892707d72536d5dc/cffi-1.16.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1b8ebc27c014c59692bb2664c7d13ce7a6e9a629be20e54e7271fa696ff2b417", size = 176745 }, - { url = "https://files.pythonhosted.org/packages/58/ac/2a3ea436a6cbaa8f75ddcab39010e5e0817a18f26fef5d2fe2e0c7df3425/cffi-1.16.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ee07e47c12890ef248766a6e55bd38ebfb2bb8edd4142d56db91b21ea68b7627", size = 443787 }, - { url = "https://files.pythonhosted.org/packages/b5/23/ea84dd4985649fcc179ba3a6c9390412e924d20b0244dc71a6545788f5a2/cffi-1.16.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8a9d3ebe49f084ad71f9269834ceccbf398253c9fac910c4fd7053ff1386936", size = 466550 }, - { url = "https://files.pythonhosted.org/packages/36/44/124481b75d228467950b9e81d20ec963f33517ca551f08956f2838517ece/cffi-1.16.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e70f54f1796669ef691ca07d046cd81a29cb4deb1e5f942003f401c0c4a2695d", size = 474224 }, - { url = "https://files.pythonhosted.org/packages/e4/9a/7169ae3a67a7bb9caeb2249f0617ac1458df118305c53afa3dec4a9029cd/cffi-1.16.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5bf44d66cdf9e893637896c7faa22298baebcd18d1ddb6d2626a6e39793a1d56", size = 457175 }, - { url = "https://files.pythonhosted.org/packages/9b/89/a31c81e36bbb793581d8bba4406a8aac4ba84b2559301c44eef81f4cf5df/cffi-1.16.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7b78010e7b97fef4bee1e896df8a4bbb6712b7f05b7ef630f9d1da00f6444d2e", size = 464825 }, - { url = "https://files.pythonhosted.org/packages/e0/80/52b71420d68c4be18873318f6735c742f1172bb3b18d23f0306e6444d410/cffi-1.16.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:c6a164aa47843fb1b01e941d385aab7215563bb8816d80ff3a363a9f8448a8dc", size = 452727 }, - { url = "https://files.pythonhosted.org/packages/47/e3/b6832b1b9a1b6170c585ee2c2d30baf64d0a497c17e6623f42cfeb59c114/cffi-1.16.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e09f3ff613345df5e8c3667da1d918f9149bd623cd9070c983c013792a9a62eb", size = 476370 }, - { url = "https://files.pythonhosted.org/packages/4a/ac/a4046ab3d72536eff8bc30b39d767f69bd8be715c5e395b71cfca26f03d9/cffi-1.16.0-cp311-cp311-win32.whl", hash = "sha256:2c56b361916f390cd758a57f2e16233eb4f64bcbeee88a4881ea90fca14dc6ab", size = 172849 }, - { url = "https://files.pythonhosted.org/packages/5a/c7/694814b3757878b29da39bc2f0cf9d20295f4c1e0a0bde7971708d5f23f8/cffi-1.16.0-cp311-cp311-win_amd64.whl", hash = "sha256:db8e577c19c0fda0beb7e0d4e09e0ba74b1e4c092e0e40bfa12fe05b6f6d75ba", size = 181495 }, - { url = "https://files.pythonhosted.org/packages/22/04/1d10d5baf3faaae9b35f6c49bcf25c1be81ea68cc7ee6923206d02be85b0/cffi-1.16.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:fa3a0128b152627161ce47201262d3140edb5a5c3da88d73a1b790a959126956", size = 183322 }, - { url = "https://files.pythonhosted.org/packages/b4/f6/b28d2bfb5fca9e8f9afc9d05eae245bed9f6ba5c2897fefee7a9abeaf091/cffi-1.16.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:68e7c44931cc171c54ccb702482e9fc723192e88d25a0e133edd7aff8fcd1f6e", size = 177173 }, - { url = "https://files.pythonhosted.org/packages/9b/1a/575200306a3dfd9102ce573e7158d459a1bd7e44637e4f22a999c4fd64b1/cffi-1.16.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:abd808f9c129ba2beda4cfc53bde801e5bcf9d6e0f22f095e45327c038bfe68e", size = 453846 }, - { url = "https://files.pythonhosted.org/packages/e4/c7/c09cc6fd1828ea950e60d44e0ef5ed0b7e3396fbfb856e49ca7d629b1408/cffi-1.16.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88e2b3c14bdb32e440be531ade29d3c50a1a59cd4e51b1dd8b0865c54ea5d2e2", size = 477041 }, - { url = "https://files.pythonhosted.org/packages/b4/5f/c6e7e8d80fbf727909e4b1b5b9352082fc1604a14991b1d536bfaee5a36c/cffi-1.16.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcc8eb6d5902bb1cf6dc4f187ee3ea80a1eba0a89aba40a5cb20a5087d961357", size = 483787 }, - { url = "https://files.pythonhosted.org/packages/a3/81/5f5d61338951afa82ce4f0f777518708893b9420a8b309cc037fbf114e63/cffi-1.16.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b7be2d771cdba2942e13215c4e340bfd76398e9227ad10402a8767ab1865d2e6", size = 469137 }, - { url = "https://files.pythonhosted.org/packages/09/d4/8759cc3b2222c159add8ce3af0089912203a31610f4be4c36f98e320b4c6/cffi-1.16.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e715596e683d2ce000574bae5d07bd522c781a822866c20495e52520564f0969", size = 477578 }, - { url = "https://files.pythonhosted.org/packages/4c/00/e17e2a8df0ff5aca2edd9eeebd93e095dd2515f2dd8d591d84a3233518f6/cffi-1.16.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:2d92b25dbf6cae33f65005baf472d2c245c050b1ce709cc4588cdcdd5495b520", size = 487099 }, - { url = "https://files.pythonhosted.org/packages/c9/6e/751437067affe7ac0944b1ad4856ec11650da77f0dd8f305fae1117ef7bb/cffi-1.16.0-cp312-cp312-win32.whl", hash = "sha256:b2ca4e77f9f47c55c194982e10f058db063937845bb2b7a86c84a6cfe0aefa8b", size = 173564 }, - { url = "https://files.pythonhosted.org/packages/e9/63/e285470a4880a4f36edabe4810057bd4b562c6ddcc165eacf9c3c7210b40/cffi-1.16.0-cp312-cp312-win_amd64.whl", hash = "sha256:68678abf380b42ce21a5f2abde8efee05c114c2fdb2e9eef2efdb0257fba1235", size = 181956 }, -] - -[[distribution]] +version = "1.17.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "pycparser" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/1e/bf/82c351342972702867359cfeba5693927efe0a8dd568165490144f554b18/cffi-1.17.0.tar.gz", hash = "sha256:f3157624b7558b914cb039fd1af735e5e8049a87c817cc215109ad1c8779df76", size = 516073 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/53/cc/9298fb6235522e00e47d78d6aa7f395332ef4e5f6fe124f9a03aa60600f7/cffi-1.17.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c5d97162c196ce54af6700949ddf9409e9833ef1003b4741c2b39ef46f1d9720", size = 181912 }, + { url = "https://files.pythonhosted.org/packages/e7/79/dc5334fbe60635d0846c56597a8d2af078a543ff22bc48d36551a0de62c2/cffi-1.17.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5ba5c243f4004c750836f81606a9fcb7841f8874ad8f3bf204ff5e56332b72b9", size = 178297 }, + { url = "https://files.pythonhosted.org/packages/39/d7/ef1b6b16b51ccbabaced90ff0d821c6c23567fc4b2e4a445aea25d3ceb92/cffi-1.17.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bb9333f58fc3a2296fb1d54576138d4cf5d496a2cc118422bd77835e6ae0b9cb", size = 444909 }, + { url = "https://files.pythonhosted.org/packages/29/b8/6e3c61885537d985c78ef7dd779b68109ba256263d74a2f615c40f44548d/cffi-1.17.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:435a22d00ec7d7ea533db494da8581b05977f9c37338c80bc86314bec2619424", size = 468854 }, + { url = "https://files.pythonhosted.org/packages/0b/49/adad1228e19b931e523c2731e6984717d5f9e33a2f9971794ab42815b29b/cffi-1.17.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d1df34588123fcc88c872f5acb6f74ae59e9d182a2707097f9e28275ec26a12d", size = 476890 }, + { url = "https://files.pythonhosted.org/packages/76/54/c00f075c3e7fd14d9011713bcdb5b4f105ad044c5ad948db7b1a0a7e4e78/cffi-1.17.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:df8bb0010fdd0a743b7542589223a2816bdde4d94bb5ad67884348fa2c1c67e8", size = 459374 }, + { url = "https://files.pythonhosted.org/packages/f3/b9/f163bb3fa4fbc636ee1f2a6a4598c096cdef279823ddfaa5734e556dd206/cffi-1.17.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a8b5b9712783415695663bd463990e2f00c6750562e6ad1d28e072a611c5f2a6", size = 466891 }, + { url = "https://files.pythonhosted.org/packages/31/52/72bbc95f6d06ff2e88a6fa13786be4043e542cb24748e1351aba864cb0a7/cffi-1.17.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ffef8fd58a36fb5f1196919638f73dd3ae0db1a878982b27a9a5a176ede4ba91", size = 477658 }, + { url = "https://files.pythonhosted.org/packages/67/20/d694811457eeae0c7663fa1a7ca201ce495533b646c1180d4ac25684c69c/cffi-1.17.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4e67d26532bfd8b7f7c05d5a766d6f437b362c1bf203a3a5ce3593a645e870b8", size = 453890 }, + { url = "https://files.pythonhosted.org/packages/dc/79/40cbf5739eb4f694833db5a27ce7f63e30a9b25b4a836c4f25fb7272aacc/cffi-1.17.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:45f7cd36186db767d803b1473b3c659d57a23b5fa491ad83c6d40f2af58e4dbb", size = 478254 }, + { url = "https://files.pythonhosted.org/packages/e9/eb/2c384c385cca5cae67ca10ac4ef685277680b8c552b99aedecf4ea23ff7e/cffi-1.17.0-cp311-cp311-win32.whl", hash = "sha256:a9015f5b8af1bb6837a3fcb0cdf3b874fe3385ff6274e8b7925d81ccaec3c5c9", size = 171285 }, + { url = "https://files.pythonhosted.org/packages/ca/42/74cb1e0f1b79cb64672f3cb46245b506239c1297a20c0d9c3aeb3929cb0c/cffi-1.17.0-cp311-cp311-win_amd64.whl", hash = "sha256:b50aaac7d05c2c26dfd50c3321199f019ba76bb650e346a6ef3616306eed67b0", size = 180842 }, + { url = "https://files.pythonhosted.org/packages/1a/1f/7862231350cc959a3138889d2c8d33da7042b22e923457dfd4cd487d772a/cffi-1.17.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:aec510255ce690d240f7cb23d7114f6b351c733a74c279a84def763660a2c3bc", size = 182826 }, + { url = "https://files.pythonhosted.org/packages/8b/8c/26119bf8b79e05a1c39812064e1ee7981e1f8a5372205ba5698ea4dd958d/cffi-1.17.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2770bb0d5e3cc0e31e7318db06efcbcdb7b31bcb1a70086d3177692a02256f59", size = 178494 }, + { url = "https://files.pythonhosted.org/packages/61/94/4882c47d3ad396d91f0eda6ef16d45be3d752a332663b7361933039ed66a/cffi-1.17.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:db9a30ec064129d605d0f1aedc93e00894b9334ec74ba9c6bdd08147434b33eb", size = 454459 }, + { url = "https://files.pythonhosted.org/packages/0f/7c/a6beb119ad515058c5ee1829742d96b25b2b9204ff920746f6e13bf574eb/cffi-1.17.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a47eef975d2b8b721775a0fa286f50eab535b9d56c70a6e62842134cf7841195", size = 478502 }, + { url = "https://files.pythonhosted.org/packages/61/8a/2575cd01a90e1eca96a30aec4b1ac101a6fae06c49d490ac2704fa9bc8ba/cffi-1.17.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f3e0992f23bbb0be00a921eae5363329253c3b86287db27092461c887b791e5e", size = 485381 }, + { url = "https://files.pythonhosted.org/packages/cd/66/85899f5a9f152db49646e0c77427173e1b77a1046de0191ab3b0b9a5e6e3/cffi-1.17.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6107e445faf057c118d5050560695e46d272e5301feffda3c41849641222a828", size = 470907 }, + { url = "https://files.pythonhosted.org/packages/00/13/150924609bf377140abe6e934ce0a57f3fc48f1fd956ec1f578ce97a4624/cffi-1.17.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eb862356ee9391dc5a0b3cbc00f416b48c1b9a52d252d898e5b7696a5f9fe150", size = 479074 }, + { url = "https://files.pythonhosted.org/packages/17/fd/7d73d7110155c036303b0a6462c56250e9bc2f4119d7591d27417329b4d1/cffi-1.17.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:c1c13185b90bbd3f8b5963cd8ce7ad4ff441924c31e23c975cb150e27c2bf67a", size = 484225 }, + { url = "https://files.pythonhosted.org/packages/fc/83/8353e5c9b01bb46332dac3dfb18e6c597a04ceb085c19c814c2f78a8c0d0/cffi-1.17.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:17c6d6d3260c7f2d94f657e6872591fe8733872a86ed1345bda872cfc8c74885", size = 488388 }, + { url = "https://files.pythonhosted.org/packages/73/0c/f9d5ca9a095b1fc88ef77d1f8b85d11151c374144e4606da33874e17b65b/cffi-1.17.0-cp312-cp312-win32.whl", hash = "sha256:c3b8bd3133cd50f6b637bb4322822c94c5ce4bf0d724ed5ae70afce62187c492", size = 172096 }, + { url = "https://files.pythonhosted.org/packages/72/21/8c5d285fe20a6e31d29325f1287bb0e55f7d93630a5a44cafdafb5922495/cffi-1.17.0-cp312-cp312-win_amd64.whl", hash = "sha256:dca802c8db0720ce1c49cce1149ff7b06e91ba15fa84b1d59144fef1a1bc7ac2", size = 181478 }, + { url = "https://files.pythonhosted.org/packages/17/8f/581f2f3c3464d5f7cf87c2f7a5ba9acc6976253e02d73804240964243ec2/cffi-1.17.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:6ce01337d23884b21c03869d2f68c5523d43174d4fc405490eb0091057943118", size = 182638 }, + { url = "https://files.pythonhosted.org/packages/8d/1c/c9afa66684b7039f48018eb11b229b659dfb32b7a16b88251bac106dd1ff/cffi-1.17.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:cab2eba3830bf4f6d91e2d6718e0e1c14a2f5ad1af68a89d24ace0c6b17cced7", size = 178453 }, + { url = "https://files.pythonhosted.org/packages/cc/b6/1a134d479d3a5a1ff2fabbee551d1d3f1dd70f453e081b5f70d604aae4c0/cffi-1.17.0-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:14b9cbc8f7ac98a739558eb86fabc283d4d564dafed50216e7f7ee62d0d25377", size = 454441 }, + { url = "https://files.pythonhosted.org/packages/b1/b4/e1569475d63aad8042b0935dbf62ae2a54d1e9142424e2b0e924d2d4a529/cffi-1.17.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b00e7bcd71caa0282cbe3c90966f738e2db91e64092a877c3ff7f19a1628fdcb", size = 478543 }, + { url = "https://files.pythonhosted.org/packages/d2/40/a9ad03fbd64309dec5bb70bc803a9a6772602de0ee164d7b9a6ca5a89249/cffi-1.17.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:41f4915e09218744d8bae14759f983e466ab69b178de38066f7579892ff2a555", size = 485463 }, + { url = "https://files.pythonhosted.org/packages/a6/1a/f10be60e006dd9242a24bcc2b1cd55c34c578380100f742d8c610f7a5d26/cffi-1.17.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e4760a68cab57bfaa628938e9c2971137e05ce48e762a9cb53b76c9b569f1204", size = 470854 }, + { url = "https://files.pythonhosted.org/packages/cc/b3/c035ed21aa3d39432bd749fe331ee90e4bc83ea2dbed1f71c4bc26c41084/cffi-1.17.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:011aff3524d578a9412c8b3cfaa50f2c0bd78e03eb7af7aa5e0df59b158efb2f", size = 479096 }, + { url = "https://files.pythonhosted.org/packages/00/cb/6f7edde01131de9382c89430b8e253b8c8754d66b63a62059663ceafeab2/cffi-1.17.0-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:a003ac9edc22d99ae1286b0875c460351f4e101f8c9d9d2576e78d7e048f64e0", size = 484013 }, + { url = "https://files.pythonhosted.org/packages/b9/83/8e4e8c211ea940210d293e951bf06b1bfb90f2eeee590e9778e99b4a8676/cffi-1.17.0-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:ef9528915df81b8f4c7612b19b8628214c65c9b7f74db2e34a646a0a2a0da2d4", size = 488119 }, + { url = "https://files.pythonhosted.org/packages/5e/52/3f7cfbc4f444cb4f73ff17b28690d12436dde665f67d68f1e1687908ab6c/cffi-1.17.0-cp313-cp313-win32.whl", hash = "sha256:70d2aa9fb00cf52034feac4b913181a6e10356019b18ef89bc7c12a283bf5f5a", size = 172122 }, + { url = "https://files.pythonhosted.org/packages/94/19/cf5baa07ee0f0e55eab7382459fbddaba0fdb0ba45973dd92556ae0d02db/cffi-1.17.0-cp313-cp313-win_amd64.whl", hash = "sha256:b7b6ea9e36d32582cda3465f54c4b454f62f23cb083ebc7a94e2ca6ef011c3a7", size = 181504 }, +] + +[[package]] name = "charset-normalizer" version = "3.3.2" source = { registry = "https://pypi.org/simple" } @@ -292,7 +311,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/28/76/e6222113b83e3622caa4bb41032d0b1bf785250607392e1b778aca0b8a7d/charset_normalizer-3.3.2-py3-none-any.whl", hash = "sha256:3e4d1f6587322d2788836a99c69062fbb091331ec940e02d12d179c1d53e25fc", size = 48543 }, ] -[[distribution]] +[[package]] name = "click" version = "8.1.7" source = { registry = "https://pypi.org/simple" } @@ -304,7 +323,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/00/2e/d53fa4befbf2cfa713304affc7ca780ce4fc1fd8710527771b58311a3229/click-8.1.7-py3-none-any.whl", hash = "sha256:ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28", size = 97941 }, ] -[[distribution]] +[[package]] name = "cloudpickle" version = "3.0.0" source = { registry = "https://pypi.org/simple" } @@ -313,7 +332,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/96/43/dae06432d0c4b1dc9e9149ad37b4ca8384cf6eb7700cd9215b177b914f0a/cloudpickle-3.0.0-py3-none-any.whl", hash = "sha256:246ee7d0c295602a036e86369c77fecda4ab17b506496730f2f576d9016fd9c7", size = 20088 }, ] -[[distribution]] +[[package]] name = "codespell" version = "2.3.0" source = { registry = "https://pypi.org/simple" } @@ -322,7 +341,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0e/20/b6019add11e84f821184234cea0ad91442373489ef7ccfa3d73a71b908fa/codespell-2.3.0-py3-none-any.whl", hash = "sha256:a9c7cef2501c9cfede2110fd6d4e5e62296920efe9abfb84648df866e47f58d1", size = 329167 }, ] -[[distribution]] +[[package]] name = "colorama" version = "0.4.6" source = { registry = "https://pypi.org/simple" } @@ -331,24 +350,24 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d1/d6/3965ed04c63042e047cb6a3e6ed1a63a35087b6a609aa3a15ed8ac56c221/colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6", size = 25335 }, ] -[[distribution]] +[[package]] name = "coloredlogs" version = "15.0.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "humanfriendly", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "humanfriendly" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cc/c7/eed8f27100517e8c0e6b923d5f0845d0cb99763da6fdee00478f91db7325/coloredlogs-15.0.1.tar.gz", hash = "sha256:7c991aa71a4577af2f82600d8f8f3a89f936baeaf9b50a9c197da014e5bf16b0", size = 278520 } wheels = [ { url = "https://files.pythonhosted.org/packages/a7/06/3d6badcf13db419e25b07041d9c7b4a2c331d3f4e7134445ec5df57714cd/coloredlogs-15.0.1-py2.py3-none-any.whl", hash = "sha256:612ee75c546f53e92e70049c9dbfcc18c935a2b9a53b66085ce9ef6a6e5c0934", size = 46018 }, ] -[[distribution]] +[[package]] name = "contourpy" version = "1.2.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8d/9e/e4786569b319847ffd98a8326802d5cf8a5500860dbfc2df1f0f4883ed99/contourpy-1.2.1.tar.gz", hash = "sha256:4d8908b3bee1c889e547867ca4cdc54e5ab6be6d3e078556814a22457f49423c", size = 13457196 } wheels = [ @@ -374,7 +393,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/78/38/a046bb0ebce6f530175d434e7364149e338ffe1069ee286ed8ba7f6481ee/contourpy-1.2.1-cp312-cp312-win_amd64.whl", hash = "sha256:1a07fc092a4088ee952ddae19a2b2a85757b923217b7eed584fdf25f53a6e7ce", size = 189901 }, ] -[[distribution]] +[[package]] name = "coverage" version = "7.6.1" source = { registry = "https://pypi.org/simple" } @@ -422,13 +441,18 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9f/b0/e0dca6da9170aefc07515cce067b97178cefafb512d00a87a1c717d2efd5/coverage-7.6.1-cp313-cp313t-win_amd64.whl", hash = "sha256:b9f222de8cded79c49bf184bdbc06630d4c58eec9459b939b4a690c82ed05657", size = 211453 }, ] -[[distribution]] +[package.optional-dependencies] +toml = [ + { name = "tomli", marker = "python_full_version == '3.11'" }, +] + +[[package]] name = "crcmod" version = "1.7" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/6b/b0/e595ce2a2527e169c3bcd6c33d2473c1918e0b7f6826a043ca1245dd4e5b/crcmod-1.7.tar.gz", hash = "sha256:dc7051a0db5f2bd48665a990d3ec1cc305a466a77358ca4492826f41f283601e", size = 89670 } -[[distribution]] +[[package]] name = "cryptography" version = "43.0.0" source = { registry = "https://pypi.org/simple" } @@ -457,7 +481,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e6/3d/696e7a0f04555c58a2813d47aaa78cb5ba863c1f453c74a4f45ae772b054/cryptography-43.0.0-cp39-abi3-win_amd64.whl", hash = "sha256:0663585d02f76929792470451a5ba64424acc3cd5227b03921dab0e2f27b1709", size = 3081462 }, ] -[[distribution]] +[[package]] name = "cycler" version = "0.12.1" source = { registry = "https://pypi.org/simple" } @@ -466,7 +490,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e7/05/c19819d5e3d95294a6f5947fb9b9629efb316b96de511b418c53d245aae6/cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30", size = 8321 }, ] -[[distribution]] +[[package]] name = "cython" version = "3.0.11" source = { registry = "https://pypi.org/simple" } @@ -499,7 +523,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/43/39/bdbec9142bc46605b54d674bf158a78b191c2b75be527c6dcf3e6dfe90b8/Cython-3.0.11-py2.py3-none-any.whl", hash = "sha256:0e25f6425ad4a700d7f77cd468da9161e63658837d1bc34861a9861a4ef6346d", size = 1171267 }, ] -[[distribution]] +[[package]] name = "dictdiffer" version = "0.9.0" source = { registry = "https://pypi.org/simple" } @@ -508,7 +532,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/47/ef/4cb333825d10317a36a1154341ba37e6e9c087bac99c1990ef07ffdb376f/dictdiffer-0.9.0-py2.py3-none-any.whl", hash = "sha256:442bfc693cfcadaf46674575d2eba1c53b42f5e404218ca2c2ff549f2df56595", size = 16754 }, ] -[[distribution]] +[[package]] name = "dnspython" version = "2.6.1" source = { registry = "https://pypi.org/simple" } @@ -517,19 +541,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/87/a1/8c5287991ddb8d3e4662f71356d9656d91ab3a36618c3dd11b280df0d255/dnspython-2.6.1-py3-none-any.whl", hash = "sha256:5ef3b9680161f6fa89daf8ad451b5f1a33b18ae8a1c6778cdf4b43f08c0a6e50", size = 307696 }, ] -[[distribution]] +[[package]] name = "ewmhlib" version = "0.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "python-xlib", marker = "sys_platform == 'linux'" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "typing-extensions" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/2f/3a/46ca34abf0725a754bc44ef474ad34aedcc3ea23b052d97b18b76715a6a9/EWMHlib-0.2-py3-none-any.whl", hash = "sha256:f5b07d8cfd4c7734462ee744c32d490f2f3233fa7ab354240069344208d2f6f5", size = 46657 }, ] -[[distribution]] +[[package]] name = "execnet" version = "2.1.1" source = { registry = "https://pypi.org/simple" } @@ -538,7 +562,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/43/09/2aea36ff60d16dd8879bdb2f5b3ee0ba8d08cbbdcdfe870e695ce3784385/execnet-2.1.1-py3-none-any.whl", hash = "sha256:26dee51f1b80cebd6d0ca8e74dd8745419761d3bef34163928cbebbdc4749fdc", size = 40612 }, ] -[[distribution]] +[[package]] name = "farama-notifications" version = "0.0.4" source = { registry = "https://pypi.org/simple" } @@ -547,7 +571,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/05/2c/ffc08c54c05cdce6fbed2aeebc46348dbe180c6d2c541c7af7ba0aa5f5f8/Farama_Notifications-0.0.4-py3-none-any.whl", hash = "sha256:14de931035a41961f7c056361dc7f980762a143d05791ef5794a751a2caf05ae", size = 2511 }, ] -[[distribution]] +[[package]] name = "filelock" version = "3.15.4" source = { registry = "https://pypi.org/simple" } @@ -556,7 +580,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ae/f0/48285f0262fe47103a4a45972ed2f9b93e4c80b8fd609fa98da78b2a5706/filelock-3.15.4-py3-none-any.whl", hash = "sha256:6ca1fffae96225dab4c6eaf1c4f4f28cd2568d3ec2a44e15a08520504de468e7", size = 16159 }, ] -[[distribution]] +[[package]] name = "flaky" version = "3.8.1" source = { registry = "https://pypi.org/simple" } @@ -565,7 +589,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7f/b8/b830fc43663246c3f3dd1ae7dca4847b96ed992537e85311e27fa41ac40e/flaky-3.8.1-py2.py3-none-any.whl", hash = "sha256:194ccf4f0d3a22b2de7130f4b62e45e977ac1b5ccad74d4d48f3005dcc38815e", size = 19139 }, ] -[[distribution]] +[[package]] name = "flatbuffers" version = "24.3.25" source = { registry = "https://pypi.org/simple" } @@ -574,7 +598,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/41/f0/7e988a019bc54b2dbd0ad4182ef2d53488bb02e58694cd79d61369e85900/flatbuffers-24.3.25-py2.py3-none-any.whl", hash = "sha256:8dbdec58f935f3765e4f7f3cf635ac3a77f83568138d6a2311f524ec96364812", size = 26784 }, ] -[[distribution]] +[[package]] name = "fonttools" version = "4.53.1" source = { registry = "https://pypi.org/simple" } @@ -599,7 +623,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e4/b9/0394d67056d4ad36a3807b439571934b318f1df925593a95e9ec0516b1a7/fonttools-4.53.1-py3-none-any.whl", hash = "sha256:f1f8758a2ad110bd6432203a344269f445a2907dc24ef6bccfd0ac4e14e0d71d", size = 1090472 }, ] -[[distribution]] +[[package]] name = "frozenlist" version = "1.4.1" source = { registry = "https://pypi.org/simple" } @@ -638,7 +662,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/83/10/466fe96dae1bff622021ee687f68e5524d6392b0a2f80d05001cd3a451ba/frozenlist-1.4.1-py3-none-any.whl", hash = "sha256:04ced3e6a46b4cfffe20f9ae482818e34eba9b5fb0ce4056e4cc9b6e212d09b7", size = 11552 }, ] -[[distribution]] +[[package]] name = "future-fstrings" version = "1.2.0" source = { registry = "https://pypi.org/simple" } @@ -647,36 +671,36 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ab/6d/ea1d52e9038558dd37f5d30647eb9f07888c164960a5d4daa5f970c6da25/future_fstrings-1.2.0-py2.py3-none-any.whl", hash = "sha256:90e49598b553d8746c4dc7d9442e0359d038c3039d802c91c0a55505da318c63", size = 6138 }, ] -[[distribution]] +[[package]] name = "geopandas" version = "1.0.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pandas", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyogrio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyproj", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "shapely", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, + { name = "packaging" }, + { name = "pandas" }, + { name = "pyogrio" }, + { name = "pyproj" }, + { name = "shapely" }, ] sdist = { url = "https://files.pythonhosted.org/packages/39/08/2cf5d85356e45b10b8d066cf4c3ba1e9e3185423c48104eed87e8afd0455/geopandas-1.0.1.tar.gz", hash = "sha256:b8bf70a5534588205b7a56646e2082fb1de9a03599651b3d80c99ea4c2ca08ab", size = 317736 } wheels = [ { url = "https://files.pythonhosted.org/packages/c4/64/7d344cfcef5efddf9cf32f59af7f855828e9d74b5f862eddf5bfd9f25323/geopandas-1.0.1-py3-none-any.whl", hash = "sha256:01e147d9420cc374d26f51fc23716ac307f32b49406e4bd8462c07e82ed1d3d6", size = 323587 }, ] -[[distribution]] +[[package]] name = "ghp-import" version = "2.1.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "python-dateutil", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "python-dateutil" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d9/29/d40217cbe2f6b1359e00c6c307bb3fc876ba74068cbab3dde77f03ca0dc4/ghp-import-2.1.0.tar.gz", hash = "sha256:9c535c4c61193c2df8871222567d7fd7e5014d835f97dc7b7439069e2413d343", size = 10943 } wheels = [ { url = "https://files.pythonhosted.org/packages/f7/ec/67fbef5d497f86283db54c22eec6f6140243aae73265799baaaa19cd17fb/ghp_import-2.1.0-py3-none-any.whl", hash = "sha256:8337dd7b50877f163d4c0289bc1f1c7f127550241988d568c1db512c4324a619", size = 11034 }, ] -[[distribution]] +[[package]] name = "google-crc32c" version = "1.5.0" source = { registry = "https://pypi.org/simple" } @@ -694,12 +718,12 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ce/8b/02bf4765c487901c8660290ade9929d65a6151c367ba32e75d136ef2d0eb/google_crc32c-1.5.0-cp311-cp311-win_amd64.whl", hash = "sha256:ba1eb1843304b1e5537e1fca632fa894d6f6deca8d6389636ee5b4797affb968", size = 27318 }, ] -[[distribution]] +[[package]] name = "grimp" version = "3.4.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/94/6c/6b071cc23c6c643b333af6f54147b59687e79b3a49bba80b4a0627bc5d90/grimp-3.4.1.tar.gz", hash = "sha256:c743c989ea49582171a93ac5aa0d22ecf04fd57143f956b3e35b6a1c7cddafec", size = 833762 } wheels = [ @@ -735,22 +759,22 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/00/ab/fd0b42471e3bc167761e1406732b57ba9448fa7ecb9bc9af97dd55fe1c3c/grimp-3.4.1-cp313-none-win_amd64.whl", hash = "sha256:17edd54ad125a9650c8dc9ca7a57ba913043ace3f7053e51ffa900236f8fddc9", size = 239009 }, ] -[[distribution]] +[[package]] name = "gymnasium" version = "0.29.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cloudpickle", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "farama-notifications", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "cloudpickle" }, + { name = "farama-notifications" }, + { name = "numpy" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0d/f8/5699ddb3e1c4f6d97b8930e573074849b921da8374fccd141f0f3a9bd713/gymnasium-0.29.1.tar.gz", hash = "sha256:1a532752efcb7590478b1cc7aa04f608eb7a2fdad5570cd217b66b6a35274bb1", size = 820485 } wheels = [ { url = "https://files.pythonhosted.org/packages/a8/4d/3cbfd81ed84db450dbe73a89afcd8bc405273918415649ac6683356afe92/gymnasium-0.29.1-py3-none-any.whl", hash = "sha256:61c3384b5575985bb7f85e43213bcb40f36fcdff388cae6bc229304c71f2843e", size = 953939 }, ] -[[distribution]] +[[package]] name = "humanfriendly" version = "10.0" source = { registry = "https://pypi.org/simple" } @@ -762,20 +786,20 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f0/0f/310fb31e39e2d734ccaa2c0fb981ee41f7bd5056ce9bc29b2248bd569169/humanfriendly-10.0-py2.py3-none-any.whl", hash = "sha256:1697e1a8a8f550fd43c2865cd84542fc175a61dcb779b6fee18cf6b6ccba1477", size = 86794 }, ] -[[distribution]] +[[package]] name = "hypothesis" version = "6.47.5" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "attrs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "sortedcontainers", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "attrs" }, + { name = "sortedcontainers" }, ] sdist = { url = "https://files.pythonhosted.org/packages/45/f2/f77da8271b1abb630cb2090ead2f5aa4acc9639d632e8e68187f52527e4b/hypothesis-6.47.5.tar.gz", hash = "sha256:e0c1e253fc97e7ecdb9e2bbff2cf815d8739e0d1d3d093d67c3af5bb6a7211b0", size = 326641 } wheels = [ { url = "https://files.pythonhosted.org/packages/d3/a7/389bbaade2cbbb2534cb2715986041ed01c6d792152c527e71f7f68e93b5/hypothesis-6.47.5-py3-none-any.whl", hash = "sha256:87049b781ee11ec1c7948565b889ab02e428a1e32d427ab4de8fdb3649242d06", size = 387311 }, ] -[[distribution]] +[[package]] name = "idna" version = "3.7" source = { registry = "https://pypi.org/simple" } @@ -784,7 +808,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e5/3e/741d8c82801c347547f8a2a06aa57dbb1992be9e948df2ea0eda2c8b79e8/idna-3.7-py3-none-any.whl", hash = "sha256:82fee1fc78add43492d3a1898bfa6d8a904cc97d8427f683ed8e798d07761aa0", size = 66836 }, ] -[[distribution]] +[[package]] name = "ifaddr" version = "0.2.0" source = { registry = "https://pypi.org/simple" } @@ -793,33 +817,33 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9c/1f/19ebc343cc71a7ffa78f17018535adc5cbdd87afb31d7c34874680148b32/ifaddr-0.2.0-py3-none-any.whl", hash = "sha256:085e0305cfe6f16ab12d72e2024030f5d52674afad6911bb1eee207177b8a748", size = 12314 }, ] -[[distribution]] +[[package]] name = "import-linter" version = "2.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "click", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "grimp", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "click" }, + { name = "grimp" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d4/3a/6b433eace42d2f92cb96667f326b11582004b74acd045bf10a277761eed4/import-linter-2.0.tar.gz", hash = "sha256:b067cf0cdbf11c4f87524e32c2e3eaa62d46572e9e06511e6b453198b15b1c9a", size = 28678 } wheels = [ { url = "https://files.pythonhosted.org/packages/81/82/5a23aefe774927b45d9964282496c5228d537bb5de1e54eedce832fa4901/import_linter-2.0-py3-none-any.whl", hash = "sha256:200f9b46d20a055c1f6f514e4cd8074852261bc9c8733d028201a55be6058bb0", size = 41018 }, ] -[[distribution]] +[[package]] name = "importlib-metadata" version = "8.2.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "zipp", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "zipp" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f6/a1/db39a513aa99ab3442010a994eef1cb977a436aded53042e69bee6959f74/importlib_metadata-8.2.0.tar.gz", hash = "sha256:72e8d4399996132204f9a16dcc751af254a48f8d1b20b9ff0f98d4a8f901e73d", size = 53907 } wheels = [ { url = "https://files.pythonhosted.org/packages/82/47/bb25ec04985d0693da478797c3d8c1092b140f3a53ccb984fbbd38affa5b/importlib_metadata-8.2.0-py3-none-any.whl", hash = "sha256:11901fa0c2f97919b288679932bb64febaeacf289d18ac84dd68cb2e74213369", size = 25920 }, ] -[[distribution]] +[[package]] name = "iniconfig" version = "2.0.0" source = { registry = "https://pypi.org/simple" } @@ -828,7 +852,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ef/a6/62565a6e1cf69e10f5727360368e451d4b7f58beeac6173dc9db836a5b46/iniconfig-2.0.0-py3-none-any.whl", hash = "sha256:b6a85871a79d2e3b22d2d1b94ac2824226a63c6b741c88f7ae975f18b6778374", size = 5892 }, ] -[[distribution]] +[[package]] name = "inputs" version = "0.5" source = { registry = "https://pypi.org/simple" } @@ -837,31 +861,31 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d0/94/040a0d9c81f018c39bd887b7b825013b024deb0a6c795f9524797e2cd41b/inputs-0.5-py2.py3-none-any.whl", hash = "sha256:13f894564e52134cf1e3862b1811da034875eb1f2b62e6021e3776e9669a96ec", size = 33630 }, ] -[[distribution]] +[[package]] name = "isodate" version = "0.6.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "six", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "six" }, ] sdist = { url = "https://files.pythonhosted.org/packages/db/7a/c0a56c7d56c7fa723988f122fa1f1ccf8c5c4ccc48efad0d214b49e5b1af/isodate-0.6.1.tar.gz", hash = "sha256:48c5881de7e8b0a0d648cb024c8062dc84e7b840ed81e864c7614fd3c127bde9", size = 28443 } wheels = [ { url = "https://files.pythonhosted.org/packages/b6/85/7882d311924cbcfc70b1890780763e36ff0b140c7e51c110fc59a532f087/isodate-0.6.1-py2.py3-none-any.whl", hash = "sha256:0751eece944162659049d35f4f549ed815792b38793f07cf73381c1c87cbed96", size = 41722 }, ] -[[distribution]] +[[package]] name = "jinja2" version = "3.1.4" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "markupsafe", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "markupsafe" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ed/55/39036716d19cab0747a5020fc7e907f362fbf48c984b14e62127f7e68e5d/jinja2-3.1.4.tar.gz", hash = "sha256:4a3aee7acbbe7303aede8e9648d13b8bf88a429282aa6122a993f0ac800cb369", size = 240245 } wheels = [ { url = "https://files.pythonhosted.org/packages/31/80/3a54838c3fb461f6fec263ebf3a3a41771bd05190238de3486aae8540c36/jinja2-3.1.4-py3-none-any.whl", hash = "sha256:bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d", size = 133271 }, ] -[[distribution]] +[[package]] name = "json-rpc" version = "1.15.0" source = { registry = "https://pypi.org/simple" } @@ -870,7 +894,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/94/9e/820c4b086ad01ba7d77369fb8b11470a01fac9b4977f02e18659cf378b6b/json_rpc-1.15.0-py2.py3-none-any.whl", hash = "sha256:4a4668bbbe7116feb4abbd0f54e64a4adcf4b8f648f19ffa0848ad0f6606a9bf", size = 39450 }, ] -[[distribution]] +[[package]] name = "kiwisolver" version = "1.4.5" source = { registry = "https://pypi.org/simple" } @@ -908,7 +932,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/63/50/2746566bdf4a6a842d117367d05c90cfb87ac04e9e2845aa1fa21f071362/kiwisolver-1.4.5-cp312-cp312-win_amd64.whl", hash = "sha256:2c5674c4e74d939b9d91dda0fae10597ac7521768fec9e399c70a1f27e2ea2d9", size = 56004 }, ] -[[distribution]] +[[package]] name = "libusb1" version = "3.1.0" source = { registry = "https://pypi.org/simple" } @@ -919,7 +943,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/02/a5/620d383ec17051f42a907f21517eb498ddecd45b2b81e46cc42e6ec4038e/libusb1-3.1.0-py3-none-win_amd64.whl", hash = "sha256:77a06ecfb3d002d7c2ce369e28d0138b292fe8db8a3d102b73fda231a716dd35", size = 140380 }, ] -[[distribution]] +[[package]] name = "lru-dict" version = "1.3.0" source = { registry = "https://pypi.org/simple" } @@ -953,57 +977,66 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/bd/18/06d9710cb0a0d3634f8501e4bdcc07abe64a32e404d82895a6a36fab97f6/lru_dict-1.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:cf9da32ef2582434842ab6ba6e67290debfae72771255a8e8ab16f3e006de0aa", size = 13811 }, ] -[[distribution]] +[[package]] name = "lxml" -version = "5.2.2" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/63/f7/ffbb6d2eb67b80a45b8a0834baa5557a14a5ffce0979439e7cd7f0c4055b/lxml-5.2.2.tar.gz", hash = "sha256:bb2dc4898180bea79863d5487e5f9c7c34297414bad54bcd0f0852aee9cfdb87", size = 3678631 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/da/6a/24e9f77d17668dd4ac0a6c2a56113fd3e0db07cee51e3a67afcd47c597e5/lxml-5.2.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:45f9494613160d0405682f9eee781c7e6d1bf45f819654eb249f8f46a2c22545", size = 8137962 }, - { url = "https://files.pythonhosted.org/packages/4e/42/3bfe92749715c819763d2205370ecc7f586b44e277f38839e27cce7d6bb8/lxml-5.2.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b0b3f2df149efb242cee2ffdeb6674b7f30d23c9a7af26595099afaf46ef4e88", size = 4424403 }, - { url = "https://files.pythonhosted.org/packages/d5/fd/4899215277e3ef1767019fab178fad8a149081f80cf886a73dc0ba1badae/lxml-5.2.2-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d28cb356f119a437cc58a13f8135ab8a4c8ece18159eb9194b0d269ec4e28083", size = 5099309 }, - { url = "https://files.pythonhosted.org/packages/15/3d/d84d07fc450af34ce49b88a5aac805b486f38c9f9305fba647a39367c51c/lxml-5.2.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:657a972f46bbefdbba2d4f14413c0d079f9ae243bd68193cb5061b9732fa54c1", size = 4810147 }, - { url = "https://files.pythonhosted.org/packages/bc/c6/32af0ec3e8323e12212c064f924ddf993017e68d1f50e03da2a3be1289c1/lxml-5.2.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b74b9ea10063efb77a965a8d5f4182806fbf59ed068b3c3fd6f30d2ac7bee734", size = 5406165 }, - { url = "https://files.pythonhosted.org/packages/67/c7/6060ea3efbd1a60a10963b1b09f493fc8f6f6728310a7a77479a3f9ab20a/lxml-5.2.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:07542787f86112d46d07d4f3c4e7c760282011b354d012dc4141cc12a68cef5f", size = 4866924 }, - { url = "https://files.pythonhosted.org/packages/8a/f7/f5df71c70c4d14d186dd86fd0e9ebeffdb63b9b86fb19fe9315f9576266b/lxml-5.2.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:303f540ad2dddd35b92415b74b900c749ec2010e703ab3bfd6660979d01fd4ed", size = 4967116 }, - { url = "https://files.pythonhosted.org/packages/4e/56/c35969591789763657eb16c2fa79c924823b97da5536da8b89e11582da89/lxml-5.2.2-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:2eb2227ce1ff998faf0cd7fe85bbf086aa41dfc5af3b1d80867ecfe75fb68df3", size = 4811365 }, - { url = "https://files.pythonhosted.org/packages/e7/28/1809a5406282c03df561a3c8143c143bd515d5668f1a138f51aec6d2618e/lxml-5.2.2-cp311-cp311-manylinux_2_28_ppc64le.whl", hash = "sha256:1d8a701774dfc42a2f0b8ccdfe7dbc140500d1049e0632a611985d943fcf12df", size = 5452505 }, - { url = "https://files.pythonhosted.org/packages/99/a1/d91217a8d7fef5ac41af87c916d322c273a9b2047c735ea1dafa2ac46d16/lxml-5.2.2-cp311-cp311-manylinux_2_28_s390x.whl", hash = "sha256:56793b7a1a091a7c286b5f4aa1fe4ae5d1446fe742d00cdf2ffb1077865db10d", size = 4973479 }, - { url = "https://files.pythonhosted.org/packages/ad/b7/0dc82afed00c4c189cfd0b83464f9a431c66de8e73d911063956a147276a/lxml-5.2.2-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:eb00b549b13bd6d884c863554566095bf6fa9c3cecb2e7b399c4bc7904cb33b5", size = 5013920 }, - { url = "https://files.pythonhosted.org/packages/5f/e0/4cd021850f2e8ab5ce6ce294556300bd4b5c1eb7def88b5f859449dc883c/lxml-5.2.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:1a2569a1f15ae6c8c64108a2cd2b4a858fc1e13d25846be0666fc144715e32ab", size = 4849156 }, - { url = "https://files.pythonhosted.org/packages/f0/f4/fb01451fda1e121eb8f117a00040454ca05a9c9d82b308272042eebd05f3/lxml-5.2.2-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:8cf85a6e40ff1f37fe0f25719aadf443686b1ac7652593dc53c7ef9b8492b115", size = 5408551 }, - { url = "https://files.pythonhosted.org/packages/2f/ca/0376418e202e9423d47f86ae09db885fa6e109d0efb602f6468e6d1e8e77/lxml-5.2.2-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:d237ba6664b8e60fd90b8549a149a74fcc675272e0e95539a00522e4ca688b04", size = 4829966 }, - { url = "https://files.pythonhosted.org/packages/74/c4/4e6f5e2be18f8eb76dff5bff3619c2c654650fee93aea37a92866efe90bc/lxml-5.2.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:0b3f5016e00ae7630a4b83d0868fca1e3d494c78a75b1c7252606a3a1c5fc2ad", size = 4976003 }, - { url = "https://files.pythonhosted.org/packages/3b/ca/5d74a0572c911f8dbf12d89abe0fdcbe0409c18978b5694392becd4d56fb/lxml-5.2.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:23441e2b5339bc54dc949e9e675fa35efe858108404ef9aa92f0456929ef6fe8", size = 4852709 }, - { url = "https://files.pythonhosted.org/packages/83/07/d95e9663ad8d875f344930e4fb52a0a6f56225267d3cc6e3e9bfa44ca736/lxml-5.2.2-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:2fb0ba3e8566548d6c8e7dd82a8229ff47bd8fb8c2da237607ac8e5a1b8312e5", size = 5479261 }, - { url = "https://files.pythonhosted.org/packages/df/e1/9ebae8d05492a8e9f632f2add15199e7bca5c1b063444e360a7bde685718/lxml-5.2.2-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:79d1fb9252e7e2cfe4de6e9a6610c7cbb99b9708e2c3e29057f487de5a9eaefa", size = 4944199 }, - { url = "https://files.pythonhosted.org/packages/ec/ab/189f571450e3393d4d442f88683d11b5a47c88e66a4e6b0d467500360483/lxml-5.2.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6dcc3d17eac1df7859ae01202e9bb11ffa8c98949dcbeb1069c8b9a75917e01b", size = 5033723 }, - { url = "https://files.pythonhosted.org/packages/80/d7/f28ccad4f08596592a58ad945c636140268bb4de9dcf4d10c9f72108d8a5/lxml-5.2.2-cp311-cp311-win32.whl", hash = "sha256:4c30a2f83677876465f44c018830f608fa3c6a8a466eb223535035fbc16f3438", size = 3475657 }, - { url = "https://files.pythonhosted.org/packages/04/19/d6aa2d980f220a04c91d4de538d2fea1a65535e7b0a4aec0998ce46e3667/lxml-5.2.2-cp311-cp311-win_amd64.whl", hash = "sha256:49095a38eb333aaf44c06052fd2ec3b8f23e19747ca7ec6f6c954ffea6dbf7be", size = 3816665 }, - { url = "https://files.pythonhosted.org/packages/26/36/6e00905cb4de2d014f4a62df58f0e82d262b5461245d951a6e7442b0222a/lxml-5.2.2-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:7429e7faa1a60cad26ae4227f4dd0459efde239e494c7312624ce228e04f6391", size = 8171540 }, - { url = "https://files.pythonhosted.org/packages/d6/68/7e9de19d47cd5430414063cd7739e8c8d8386016740c18af5ff13b64ff5c/lxml-5.2.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:50ccb5d355961c0f12f6cf24b7187dbabd5433f29e15147a67995474f27d1776", size = 4441241 }, - { url = "https://files.pythonhosted.org/packages/b4/1f/6a88a8e1b6a9be644c74e5f72cf581cb342a392e020c60a389cd194ebba1/lxml-5.2.2-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dc911208b18842a3a57266d8e51fc3cfaccee90a5351b92079beed912a7914c2", size = 5052926 }, - { url = "https://files.pythonhosted.org/packages/6b/cc/8e73a63c2aeb205fbed44272fea8c5ded07920233b9956e8e304e2516931/lxml-5.2.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:33ce9e786753743159799fdf8e92a5da351158c4bfb6f2db0bf31e7892a1feb5", size = 4748543 }, - { url = "https://files.pythonhosted.org/packages/ae/fc/6020fe1468fccb684619df6765a79b67229091631e5f14b97c3efcd75ca7/lxml-5.2.2-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ec87c44f619380878bd49ca109669c9f221d9ae6883a5bcb3616785fa8f94c97", size = 5320915 }, - { url = "https://files.pythonhosted.org/packages/25/6c/02cecb6a26b0baec373baa3f4fb55343cf0d8710d6a853ff4c4b12a9cf16/lxml-5.2.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:08ea0f606808354eb8f2dfaac095963cb25d9d28e27edcc375d7b30ab01abbf6", size = 4814179 }, - { url = "https://files.pythonhosted.org/packages/de/12/0253de661bb9f8c26b47059be4ed2ec5b9e4411fd2b1d45a2f4b399a7616/lxml-5.2.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:75a9632f1d4f698b2e6e2e1ada40e71f369b15d69baddb8968dcc8e683839b18", size = 4923168 }, - { url = "https://files.pythonhosted.org/packages/cd/e7/63435cfa76534fb33a9656507057b96a25bb850ae932424b9724c9fe379e/lxml-5.2.2-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:74da9f97daec6928567b48c90ea2c82a106b2d500f397eeb8941e47d30b1ca85", size = 4741798 }, - { url = "https://files.pythonhosted.org/packages/27/7f/9e203e850609fa12c8b347fcceaba8655f062bc19ace7a837bb7fcf64b8f/lxml-5.2.2-cp312-cp312-manylinux_2_28_ppc64le.whl", hash = "sha256:0969e92af09c5687d769731e3f39ed62427cc72176cebb54b7a9d52cc4fa3b73", size = 5347143 }, - { url = "https://files.pythonhosted.org/packages/d9/d2/089fcb90e6bdd16639656c2632573508ae02f42a3b034376d3e32efd2ccc/lxml-5.2.2-cp312-cp312-manylinux_2_28_s390x.whl", hash = "sha256:9164361769b6ca7769079f4d426a41df6164879f7f3568be9086e15baca61466", size = 4901745 }, - { url = "https://files.pythonhosted.org/packages/9a/87/cff3c63ebe067ec9a7cc1948c379b8a16e7990c29bd5baf77c0a1dbd03c0/lxml-5.2.2-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:d26a618ae1766279f2660aca0081b2220aca6bd1aa06b2cf73f07383faf48927", size = 4947584 }, - { url = "https://files.pythonhosted.org/packages/73/3f/5a22be26edce482cb5dbdc5cf75544cfd1d3fb1389124d06995395829617/lxml-5.2.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:ab67ed772c584b7ef2379797bf14b82df9aa5f7438c5b9a09624dd834c1c1aaf", size = 4790271 }, - { url = "https://files.pythonhosted.org/packages/b5/66/007666e7878ca746e44da3b4c2acf9d5c617dd51e152e89589e7eeb59f87/lxml-5.2.2-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:3d1e35572a56941b32c239774d7e9ad724074d37f90c7a7d499ab98761bd80cf", size = 5340401 }, - { url = "https://files.pythonhosted.org/packages/9d/3e/b7464d5c06a57cb206fd14a9251bfa75ae03d4f6b1c0c41cf82111bdfa3b/lxml-5.2.2-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:8268cbcd48c5375f46e000adb1390572c98879eb4f77910c6053d25cc3ac2c67", size = 4784839 }, - { url = "https://files.pythonhosted.org/packages/5b/70/1c45927de1cd7dc47292cfa8a9eb7928b38ce5647d66601bd169b25af4a7/lxml-5.2.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:e282aedd63c639c07c3857097fc0e236f984ceb4089a8b284da1c526491e3f3d", size = 4933979 }, - { url = "https://files.pythonhosted.org/packages/08/e1/51f6ad2bdb5f28fceeb6bd591d4a0ed5de42ffc6741fd88eb2209c6a46f2/lxml-5.2.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6dfdc2bfe69e9adf0df4915949c22a25b39d175d599bf98e7ddf620a13678585", size = 4782412 }, - { url = "https://files.pythonhosted.org/packages/81/13/7df8804d4fb678e0216f6f4532754fd471856b5cb24726dab55a3b65f527/lxml-5.2.2-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:4aefd911793b5d2d7a921233a54c90329bf3d4a6817dc465f12ffdfe4fc7b8fe", size = 5371318 }, - { url = "https://files.pythonhosted.org/packages/d7/7d/c98b7ef3e496a9c371057dc955be1fda04dab4e8af488b01bec254e1b59b/lxml-5.2.2-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:8b8df03a9e995b6211dafa63b32f9d405881518ff1ddd775db4e7b98fb545e1c", size = 4871432 }, - { url = "https://files.pythonhosted.org/packages/3e/fa/b361d670ffa8f477504b7fc0e5734a7878815c7e0b6769f3a5a903a94aee/lxml-5.2.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f11ae142f3a322d44513de1018b50f474f8f736bc3cd91d969f464b5bfef8836", size = 4972719 }, - { url = "https://files.pythonhosted.org/packages/fc/43/70e469a190a8f39ca5829b4ef4f2f7299ce65243abe46ba4a73dc58c1365/lxml-5.2.2-cp312-cp312-win32.whl", hash = "sha256:16a8326e51fcdffc886294c1e70b11ddccec836516a343f9ed0f82aac043c24a", size = 3487299 }, - { url = "https://files.pythonhosted.org/packages/58/16/99b03974974537c8c786fb98183d7c213ceb16e71205174a29ae869ca988/lxml-5.2.2-cp312-cp312-win_amd64.whl", hash = "sha256:bbc4b80af581e18568ff07f6395c02114d05f4865c2812a1f02f2eaecf0bfd48", size = 3817779 }, -] - -[[distribution]] +version = "5.3.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/e7/6b/20c3a4b24751377aaa6307eb230b66701024012c29dd374999cc92983269/lxml-5.3.0.tar.gz", hash = "sha256:4e109ca30d1edec1ac60cdbe341905dc3b8f55b16855e03a54aaf59e51ec8c6f", size = 3679318 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/5c/a8/449faa2a3cbe6a99f8d38dcd51a3ee8844c17862841a6f769ea7c2a9cd0f/lxml-5.3.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:74bcb423462233bc5d6066e4e98b0264e7c1bed7541fff2f4e34fe6b21563c8b", size = 8141056 }, + { url = "https://files.pythonhosted.org/packages/ac/8a/ae6325e994e2052de92f894363b038351c50ee38749d30cc6b6d96aaf90f/lxml-5.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a3d819eb6f9b8677f57f9664265d0a10dd6551d227afb4af2b9cd7bdc2ccbf18", size = 4425238 }, + { url = "https://files.pythonhosted.org/packages/f8/fb/128dddb7f9086236bce0eeae2bfb316d138b49b159f50bc681d56c1bdd19/lxml-5.3.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5b8f5db71b28b8c404956ddf79575ea77aa8b1538e8b2ef9ec877945b3f46442", size = 5095197 }, + { url = "https://files.pythonhosted.org/packages/b4/f9/a181a8ef106e41e3086629c8bdb2d21a942f14c84a0e77452c22d6b22091/lxml-5.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c3406b63232fc7e9b8783ab0b765d7c59e7c59ff96759d8ef9632fca27c7ee4", size = 4809809 }, + { url = "https://files.pythonhosted.org/packages/25/2f/b20565e808f7f6868aacea48ddcdd7e9e9fb4c799287f21f1a6c7c2e8b71/lxml-5.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:2ecdd78ab768f844c7a1d4a03595038c166b609f6395e25af9b0f3f26ae1230f", size = 5407593 }, + { url = "https://files.pythonhosted.org/packages/23/0e/caac672ec246d3189a16c4d364ed4f7d6bf856c080215382c06764058c08/lxml-5.3.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:168f2dfcfdedf611eb285efac1516c8454c8c99caf271dccda8943576b67552e", size = 4866657 }, + { url = "https://files.pythonhosted.org/packages/67/a4/1f5fbd3f58d4069000522196b0b776a014f3feec1796da03e495cf23532d/lxml-5.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:aa617107a410245b8660028a7483b68e7914304a6d4882b5ff3d2d3eb5948d8c", size = 4967017 }, + { url = "https://files.pythonhosted.org/packages/ee/73/623ecea6ca3c530dd0a4ed0d00d9702e0e85cd5624e2d5b93b005fe00abd/lxml-5.3.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:69959bd3167b993e6e710b99051265654133a98f20cec1d9b493b931942e9c16", size = 4810730 }, + { url = "https://files.pythonhosted.org/packages/1d/ce/fb84fb8e3c298f3a245ae3ea6221c2426f1bbaa82d10a88787412a498145/lxml-5.3.0-cp311-cp311-manylinux_2_28_ppc64le.whl", hash = "sha256:bd96517ef76c8654446fc3db9242d019a1bb5fe8b751ba414765d59f99210b79", size = 5455154 }, + { url = "https://files.pythonhosted.org/packages/b1/72/4d1ad363748a72c7c0411c28be2b0dc7150d91e823eadad3b91a4514cbea/lxml-5.3.0-cp311-cp311-manylinux_2_28_s390x.whl", hash = "sha256:ab6dd83b970dc97c2d10bc71aa925b84788c7c05de30241b9e96f9b6d9ea3080", size = 4969416 }, + { url = "https://files.pythonhosted.org/packages/42/07/b29571a58a3a80681722ea8ed0ba569211d9bb8531ad49b5cacf6d409185/lxml-5.3.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:eec1bb8cdbba2925bedc887bc0609a80e599c75b12d87ae42ac23fd199445654", size = 5013672 }, + { url = "https://files.pythonhosted.org/packages/b9/93/bde740d5a58cf04cbd38e3dd93ad1e36c2f95553bbf7d57807bc6815d926/lxml-5.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6a7095eeec6f89111d03dabfe5883a1fd54da319c94e0fb104ee8f23616b572d", size = 4878644 }, + { url = "https://files.pythonhosted.org/packages/56/b5/645c8c02721d49927c93181de4017164ec0e141413577687c3df8ff0800f/lxml-5.3.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:6f651ebd0b21ec65dfca93aa629610a0dbc13dbc13554f19b0113da2e61a4763", size = 5511531 }, + { url = "https://files.pythonhosted.org/packages/85/3f/6a99a12d9438316f4fc86ef88c5d4c8fb674247b17f3173ecadd8346b671/lxml-5.3.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:f422a209d2455c56849442ae42f25dbaaba1c6c3f501d58761c619c7836642ec", size = 5402065 }, + { url = "https://files.pythonhosted.org/packages/80/8a/df47bff6ad5ac57335bf552babfb2408f9eb680c074ec1ba412a1a6af2c5/lxml-5.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:62f7fdb0d1ed2065451f086519865b4c90aa19aed51081979ecd05a21eb4d1be", size = 5069775 }, + { url = "https://files.pythonhosted.org/packages/08/ae/e7ad0f0fbe4b6368c5ee1e3ef0c3365098d806d42379c46c1ba2802a52f7/lxml-5.3.0-cp311-cp311-win32.whl", hash = "sha256:c6379f35350b655fd817cd0d6cbeef7f265f3ae5fedb1caae2eb442bbeae9ab9", size = 3474226 }, + { url = "https://files.pythonhosted.org/packages/c3/b5/91c2249bfac02ee514ab135e9304b89d55967be7e53e94a879b74eec7a5c/lxml-5.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:9c52100e2c2dbb0649b90467935c4b0de5528833c76a35ea1a2691ec9f1ee7a1", size = 3814971 }, + { url = "https://files.pythonhosted.org/packages/eb/6d/d1f1c5e40c64bf62afd7a3f9b34ce18a586a1cccbf71e783cd0a6d8e8971/lxml-5.3.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:e99f5507401436fdcc85036a2e7dc2e28d962550afe1cbfc07c40e454256a859", size = 8171753 }, + { url = "https://files.pythonhosted.org/packages/bd/83/26b1864921869784355459f374896dcf8b44d4af3b15d7697e9156cb2de9/lxml-5.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:384aacddf2e5813a36495233b64cb96b1949da72bef933918ba5c84e06af8f0e", size = 4441955 }, + { url = "https://files.pythonhosted.org/packages/e0/d2/e9bff9fb359226c25cda3538f664f54f2804f4b37b0d7c944639e1a51f69/lxml-5.3.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:874a216bf6afaf97c263b56371434e47e2c652d215788396f60477540298218f", size = 5050778 }, + { url = "https://files.pythonhosted.org/packages/88/69/6972bfafa8cd3ddc8562b126dd607011e218e17be313a8b1b9cc5a0ee876/lxml-5.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:65ab5685d56914b9a2a34d67dd5488b83213d680b0c5d10b47f81da5a16b0b0e", size = 4748628 }, + { url = "https://files.pythonhosted.org/packages/5d/ea/a6523c7c7f6dc755a6eed3d2f6d6646617cad4d3d6d8ce4ed71bfd2362c8/lxml-5.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:aac0bbd3e8dd2d9c45ceb82249e8bdd3ac99131a32b4d35c8af3cc9db1657179", size = 5322215 }, + { url = "https://files.pythonhosted.org/packages/99/37/396fbd24a70f62b31d988e4500f2068c7f3fd399d2fd45257d13eab51a6f/lxml-5.3.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b369d3db3c22ed14c75ccd5af429086f166a19627e84a8fdade3f8f31426e52a", size = 4813963 }, + { url = "https://files.pythonhosted.org/packages/09/91/e6136f17459a11ce1757df864b213efbeab7adcb2efa63efb1b846ab6723/lxml-5.3.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c24037349665434f375645fa9d1f5304800cec574d0310f618490c871fd902b3", size = 4923353 }, + { url = "https://files.pythonhosted.org/packages/1d/7c/2eeecf87c9a1fca4f84f991067c693e67340f2b7127fc3eca8fa29d75ee3/lxml-5.3.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:62d172f358f33a26d6b41b28c170c63886742f5b6772a42b59b4f0fa10526cb1", size = 4740541 }, + { url = "https://files.pythonhosted.org/packages/3b/ed/4c38ba58defca84f5f0d0ac2480fdcd99fc7ae4b28fc417c93640a6949ae/lxml-5.3.0-cp312-cp312-manylinux_2_28_ppc64le.whl", hash = "sha256:c1f794c02903c2824fccce5b20c339a1a14b114e83b306ff11b597c5f71a1c8d", size = 5346504 }, + { url = "https://files.pythonhosted.org/packages/a5/22/bbd3995437e5745cb4c2b5d89088d70ab19d4feabf8a27a24cecb9745464/lxml-5.3.0-cp312-cp312-manylinux_2_28_s390x.whl", hash = "sha256:5d6a6972b93c426ace71e0be9a6f4b2cfae9b1baed2eed2006076a746692288c", size = 4898077 }, + { url = "https://files.pythonhosted.org/packages/0a/6e/94537acfb5b8f18235d13186d247bca478fea5e87d224644e0fe907df976/lxml-5.3.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:3879cc6ce938ff4eb4900d901ed63555c778731a96365e53fadb36437a131a99", size = 4946543 }, + { url = "https://files.pythonhosted.org/packages/8d/e8/4b15df533fe8e8d53363b23a41df9be907330e1fa28c7ca36893fad338ee/lxml-5.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:74068c601baff6ff021c70f0935b0c7bc528baa8ea210c202e03757c68c5a4ff", size = 4816841 }, + { url = "https://files.pythonhosted.org/packages/1a/e7/03f390ea37d1acda50bc538feb5b2bda6745b25731e4e76ab48fae7106bf/lxml-5.3.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:ecd4ad8453ac17bc7ba3868371bffb46f628161ad0eefbd0a855d2c8c32dd81a", size = 5417341 }, + { url = "https://files.pythonhosted.org/packages/ea/99/d1133ab4c250da85a883c3b60249d3d3e7c64f24faff494cf0fd23f91e80/lxml-5.3.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:7e2f58095acc211eb9d8b5771bf04df9ff37d6b87618d1cbf85f92399c98dae8", size = 5327539 }, + { url = "https://files.pythonhosted.org/packages/7d/ed/e6276c8d9668028213df01f598f385b05b55a4e1b4662ee12ef05dab35aa/lxml-5.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:e63601ad5cd8f860aa99d109889b5ac34de571c7ee902d6812d5d9ddcc77fa7d", size = 5012542 }, + { url = "https://files.pythonhosted.org/packages/36/88/684d4e800f5aa28df2a991a6a622783fb73cf0e46235cfa690f9776f032e/lxml-5.3.0-cp312-cp312-win32.whl", hash = "sha256:17e8d968d04a37c50ad9c456a286b525d78c4a1c15dd53aa46c1d8e06bf6fa30", size = 3486454 }, + { url = "https://files.pythonhosted.org/packages/fc/82/ace5a5676051e60355bd8fb945df7b1ba4f4fb8447f2010fb816bfd57724/lxml-5.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:c1a69e58a6bb2de65902051d57fde951febad631a20a64572677a1052690482f", size = 3816857 }, + { url = "https://files.pythonhosted.org/packages/94/6a/42141e4d373903bfea6f8e94b2f554d05506dfda522ada5343c651410dc8/lxml-5.3.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8c72e9563347c7395910de6a3100a4840a75a6f60e05af5e58566868d5eb2d6a", size = 8156284 }, + { url = "https://files.pythonhosted.org/packages/91/5e/fa097f0f7d8b3d113fb7312c6308af702f2667f22644441715be961f2c7e/lxml-5.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:e92ce66cd919d18d14b3856906a61d3f6b6a8500e0794142338da644260595cd", size = 4432407 }, + { url = "https://files.pythonhosted.org/packages/2d/a1/b901988aa6d4ff937f2e5cfc114e4ec561901ff00660c3e56713642728da/lxml-5.3.0-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1d04f064bebdfef9240478f7a779e8c5dc32b8b7b0b2fc6a62e39b928d428e51", size = 5048331 }, + { url = "https://files.pythonhosted.org/packages/30/0f/b2a54f48e52de578b71bbe2a2f8160672a8a5e103df3a78da53907e8c7ed/lxml-5.3.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5c2fb570d7823c2bbaf8b419ba6e5662137f8166e364a8b2b91051a1fb40ab8b", size = 4744835 }, + { url = "https://files.pythonhosted.org/packages/82/9d/b000c15538b60934589e83826ecbc437a1586488d7c13f8ee5ff1f79a9b8/lxml-5.3.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:0c120f43553ec759f8de1fee2f4794452b0946773299d44c36bfe18e83caf002", size = 5316649 }, + { url = "https://files.pythonhosted.org/packages/e3/ee/ffbb9eaff5e541922611d2c56b175c45893d1c0b8b11e5a497708a6a3b3b/lxml-5.3.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:562e7494778a69086f0312ec9689f6b6ac1c6b65670ed7d0267e49f57ffa08c4", size = 4812046 }, + { url = "https://files.pythonhosted.org/packages/15/ff/7ff89d567485c7b943cdac316087f16b2399a8b997007ed352a1248397e5/lxml-5.3.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:423b121f7e6fa514ba0c7918e56955a1d4470ed35faa03e3d9f0e3baa4c7e492", size = 4918597 }, + { url = "https://files.pythonhosted.org/packages/c6/a3/535b6ed8c048412ff51268bdf4bf1cf052a37aa7e31d2e6518038a883b29/lxml-5.3.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:c00f323cc00576df6165cc9d21a4c21285fa6b9989c5c39830c3903dc4303ef3", size = 4738071 }, + { url = "https://files.pythonhosted.org/packages/7a/8f/cbbfa59cb4d4fd677fe183725a76d8c956495d7a3c7f111ab8f5e13d2e83/lxml-5.3.0-cp313-cp313-manylinux_2_28_ppc64le.whl", hash = "sha256:1fdc9fae8dd4c763e8a31e7630afef517eab9f5d5d31a278df087f307bf601f4", size = 5342213 }, + { url = "https://files.pythonhosted.org/packages/5c/fb/db4c10dd9958d4b52e34d1d1f7c1f434422aeaf6ae2bbaaff2264351d944/lxml-5.3.0-cp313-cp313-manylinux_2_28_s390x.whl", hash = "sha256:658f2aa69d31e09699705949b5fc4719cbecbd4a97f9656a232e7d6c7be1a367", size = 4893749 }, + { url = "https://files.pythonhosted.org/packages/f2/38/bb4581c143957c47740de18a3281a0cab7722390a77cc6e610e8ebf2d736/lxml-5.3.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:1473427aff3d66a3fa2199004c3e601e6c4500ab86696edffdbc84954c72d832", size = 4945901 }, + { url = "https://files.pythonhosted.org/packages/fc/d5/18b7de4960c731e98037bd48fa9f8e6e8f2558e6fbca4303d9b14d21ef3b/lxml-5.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a87de7dd873bf9a792bf1e58b1c3887b9264036629a5bf2d2e6579fe8e73edff", size = 4815447 }, + { url = "https://files.pythonhosted.org/packages/97/a8/cd51ceaad6eb849246559a8ef60ae55065a3df550fc5fcd27014361c1bab/lxml-5.3.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:0d7b36afa46c97875303a94e8f3ad932bf78bace9e18e603f2085b652422edcd", size = 5411186 }, + { url = "https://files.pythonhosted.org/packages/89/c3/1e3dabab519481ed7b1fdcba21dcfb8832f57000733ef0e71cf6d09a5e03/lxml-5.3.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:cf120cce539453ae086eacc0130a324e7026113510efa83ab42ef3fcfccac7fb", size = 5324481 }, + { url = "https://files.pythonhosted.org/packages/b6/17/71e9984cf0570cd202ac0a1c9ed5c1b8889b0fc8dc736f5ef0ffb181c284/lxml-5.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:df5c7333167b9674aa8ae1d4008fa4bc17a313cc490b2cca27838bbdcc6bb15b", size = 5011053 }, + { url = "https://files.pythonhosted.org/packages/69/68/9f7e6d3312a91e30829368c2b3217e750adef12a6f8eb10498249f4e8d72/lxml-5.3.0-cp313-cp313-win32.whl", hash = "sha256:c802e1c2ed9f0c06a65bc4ed0189d000ada8049312cfeab6ca635e39c9608957", size = 3485634 }, + { url = "https://files.pythonhosted.org/packages/7d/db/214290d58ad68c587bd5d6af3d34e56830438733d0d0856c0275fde43652/lxml-5.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:406246b96d552e0503e17a1006fd27edac678b3fcc9f1be71a2f94b4ff61528d", size = 3814417 }, +] + +[[package]] name = "markdown" version = "3.6" source = { registry = "https://pypi.org/simple" } @@ -1012,7 +1045,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fc/b3/0c0c994fe49cd661084f8d5dc06562af53818cc0abefaca35bdc894577c3/Markdown-3.6-py3-none-any.whl", hash = "sha256:48f276f4d8cfb8ce6527c8f79e2ee29708508bf4d40aa410fbc3b4ee832c850f", size = 105381 }, ] -[[distribution]] +[[package]] name = "markupsafe" version = "2.1.5" source = { registry = "https://pypi.org/simple" } @@ -1040,38 +1073,38 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3f/14/c3554d512d5f9100a95e737502f4a2323a1959f6d0d01e0d0997b35f7b10/MarkupSafe-2.1.5-cp312-cp312-win_amd64.whl", hash = "sha256:823b65d8706e32ad2df51ed89496147a42a2a6e01c13cfb6ffb8b1e92bc910bb", size = 17127 }, ] -[[distribution]] +[[package]] name = "matplotlib" -version = "3.9.0" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "contourpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cycler", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "fonttools", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "kiwisolver", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pillow", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyparsing", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "python-dateutil", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/c5/a4/a7236bf8b0137deff48737c6ccf2154ef4486e57c6a5b7c309bf515992bd/matplotlib-3.9.0.tar.gz", hash = "sha256:e6d29ea6c19e34b30fb7d88b7081f869a03014f66fe06d62cc77d5a6ea88ed7a", size = 36069890 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/09/49/569b50eb5e5a75b61f7a0bacb6029e9ea9c8a1190df55a39a31789244e09/matplotlib-3.9.0-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:063af8587fceeac13b0936c42a2b6c732c2ab1c98d38abc3337e430e1ff75e38", size = 7893678 }, - { url = "https://files.pythonhosted.org/packages/f4/b4/c1700c8b2ff8d379c187f37055e61bd7a611eb2c544466600a7734793d54/matplotlib-3.9.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9a2fa6d899e17ddca6d6526cf6e7ba677738bf2a6a9590d702c277204a7c6152", size = 7775027 }, - { url = "https://files.pythonhosted.org/packages/bc/9e/b09513717f60071fefcb28c7c783aa658f939f3d4ba1cefb6c05138c6657/matplotlib-3.9.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:550cdda3adbd596078cca7d13ed50b77879104e2e46392dcd7c75259d8f00e85", size = 8192694 }, - { url = "https://files.pythonhosted.org/packages/41/f1/115e7c79b4506b4f0533acba742babd9718ff92eeca6d4205843173b6173/matplotlib-3.9.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:76cce0f31b351e3551d1f3779420cf8f6ec0d4a8cf9c0237a3b549fd28eb4abb", size = 8307002 }, - { url = "https://files.pythonhosted.org/packages/7a/a2/5c1a64d188c4cae7368ebb8c28a354e3f262cb86b28c38ffa6ee3ad532ba/matplotlib-3.9.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:c53aeb514ccbbcbab55a27f912d79ea30ab21ee0531ee2c09f13800efb272674", size = 8600548 }, - { url = "https://files.pythonhosted.org/packages/c6/c8/6936e8c7b279a5abac82f399d8d72ac25da530cf5f78a0e40063e492558c/matplotlib-3.9.0-cp311-cp311-win_amd64.whl", hash = "sha256:a5be985db2596d761cdf0c2eaf52396f26e6a64ab46bd8cd810c48972349d1be", size = 7963606 }, - { url = "https://files.pythonhosted.org/packages/af/43/54b7dfd91ed33da92973dc5d50231ef7b2d0622c8ae72babbad26bc1a319/matplotlib-3.9.0-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:c79f3a585f1368da6049318bdf1f85568d8d04b2e89fc24b7e02cc9b62017382", size = 7884612 }, - { url = "https://files.pythonhosted.org/packages/4c/88/15bbb864b0d871707294ff325f9ffd0dfa486db2637eb34dd5f8dcf5b9bf/matplotlib-3.9.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:bdd1ecbe268eb3e7653e04f451635f0fb0f77f07fd070242b44c076c9106da84", size = 7769852 }, - { url = "https://files.pythonhosted.org/packages/57/af/8ed9b852fc041fc5bd101f9964682874ccbf24f9c08323edee6a1600eb04/matplotlib-3.9.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d38e85a1a6d732f645f1403ce5e6727fd9418cd4574521d5803d3d94911038e5", size = 8185646 }, - { url = "https://files.pythonhosted.org/packages/f4/ff/da311c1e679eed54d3aed67754a4e859bd3b773060c2fa187962e60fcb85/matplotlib-3.9.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0a490715b3b9984fa609116481b22178348c1a220a4499cda79132000a79b4db", size = 8298411 }, - { url = "https://files.pythonhosted.org/packages/db/8c/1014baa6776503914865d87e1e8a803ee9faa7b722ca5e655463b79c966e/matplotlib-3.9.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8146ce83cbc5dc71c223a74a1996d446cd35cfb6a04b683e1446b7e6c73603b7", size = 8591196 }, - { url = "https://files.pythonhosted.org/packages/17/91/febbb6c1063ae05a62fdbe038c2917b348b1b35f0482cee4738e6870a44a/matplotlib-3.9.0-cp312-cp312-win_amd64.whl", hash = "sha256:d91a4ffc587bacf5c4ce4ecfe4bcd23a4b675e76315f2866e588686cc97fccdf", size = 7968581 }, -] - -[[distribution]] +version = "3.9.1.post1" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "contourpy" }, + { name = "cycler" }, + { name = "fonttools" }, + { name = "kiwisolver" }, + { name = "numpy" }, + { name = "packaging" }, + { name = "pillow" }, + { name = "pyparsing" }, + { name = "python-dateutil" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/27/c3/b4dbf9ed2a024a5514fa8a2606867a3716c9adfd457d138865145a940a65/matplotlib-3.9.1.post1.tar.gz", hash = "sha256:c91e585c65092c975a44dc9d4239ba8c594ba3c193d7c478b6d178c4ef61f406", size = 36086838 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/41/dc/1f51d34daebbfe172b78fa5b5be467554b973ef30b80ed2f6200b34d3223/matplotlib-3.9.1.post1-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:b08b46058fe2a31ecb81ef6aa3611f41d871f6a8280e9057cb4016cb3d8e894a", size = 7902785 }, + { url = "https://files.pythonhosted.org/packages/43/ef/3fadf6545a0c609c7720477b2bfa2e578f99c106e3bd1aaf591e006c3434/matplotlib-3.9.1.post1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:22b344e84fcc574f561b5731f89a7625db8ef80cdbb0026a8ea855a33e3429d1", size = 7773056 }, + { url = "https://files.pythonhosted.org/packages/c3/2b/1c9e695967edb54f0cfb1ea5d41f5482344cf245489f8a47aa427825f264/matplotlib-3.9.1.post1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4b49fee26d64aefa9f061b575f0f7b5fc4663e51f87375c7239efa3d30d908fa", size = 8202179 }, + { url = "https://files.pythonhosted.org/packages/a5/8b/90fae9c1b34ef3252003c26b15e8cb26b83701e34e5acf6430919c2c5c89/matplotlib-3.9.1.post1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:89eb7e89e2b57856533c5c98f018aa3254fa3789fcd86d5f80077b9034a54c9a", size = 8314155 }, + { url = "https://files.pythonhosted.org/packages/76/05/c1b75af3cee0c1f2a0badc8680c5f70fc2d2c1015c64253f073075acded9/matplotlib-3.9.1.post1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c06e742bade41fda6176d4c9c78c9ea016e176cd338e62a1686384cb1eb8de41", size = 9091226 }, + { url = "https://files.pythonhosted.org/packages/0a/d4/c0812c410de88e8646727a7c000741331875ae556018725ae169d206f0a2/matplotlib-3.9.1.post1-cp311-cp311-win_amd64.whl", hash = "sha256:c44edab5b849e0fc1f1c9d6e13eaa35ef65925f7be45be891d9784709ad95561", size = 7968523 }, + { url = "https://files.pythonhosted.org/packages/f1/59/657e1e363c87c217bb4b3fb2e4bf53bf461bf27ee757cc2db2d5b79ba976/matplotlib-3.9.1.post1-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:bf28b09986aee06393e808e661c3466be9c21eff443c9bc881bce04bfbb0c500", size = 7892389 }, + { url = "https://files.pythonhosted.org/packages/38/01/6c0ef66d64cf45fdb5a06096b8c7a33fb47b1293a8dbf1577edafb5fd76b/matplotlib-3.9.1.post1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:92aeb8c439d4831510d8b9d5e39f31c16c7f37873879767c26b147cef61e54cd", size = 7769231 }, + { url = "https://files.pythonhosted.org/packages/68/be/d7178c01418f081a335e48e40a58ab597cde867fde08b294310da0537452/matplotlib-3.9.1.post1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f15798b0691b45c80d3320358a88ce5a9d6f518b28575b3ea3ed31b4bd95d009", size = 8193062 }, + { url = "https://files.pythonhosted.org/packages/9e/42/70cb7ac228beb35b009fe32f4ef62cc33a68041230cee39e439b4980cf98/matplotlib-3.9.1.post1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d59fc6096da7b9c1df275f9afc3fef5cbf634c21df9e5f844cba3dd8deb1847d", size = 8306107 }, + { url = "https://files.pythonhosted.org/packages/cf/e1/4ca974dde5356a5b9958b0089343a72a845f7a82780b6f4dfa99848eafbb/matplotlib-3.9.1.post1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ab986817a32a70ce22302438691e7df4c6ee4a844d47289db9d583d873491e0b", size = 9086519 }, + { url = "https://files.pythonhosted.org/packages/cf/9d/2f0fcb11b4abc090aed00a986ed3943ad00dbe5a58414801bc39f869e844/matplotlib-3.9.1.post1-cp312-cp312-win_amd64.whl", hash = "sha256:0d78e7d2d86c4472da105d39aba9b754ed3dfeaeaa4ac7206b82706e0a5362fa", size = 7972412 }, +] + +[[package]] name = "mergedeep" version = "1.3.4" source = { registry = "https://pypi.org/simple" } @@ -1080,85 +1113,85 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2c/19/04f9b178c2d8a15b076c8b5140708fa6ffc5601fb6f1e975537072df5b2a/mergedeep-1.3.4-py3-none-any.whl", hash = "sha256:70775750742b25c0d8f36c55aed03d24c3384d17c951b3175d898bd778ef0307", size = 6354 }, ] -[[distribution]] +[[package]] name = "metadrive-simulator" version = "0.4.2.3" -source = { git = "https://github.com/commaai/metadrive?rev=opencv_headless#9b6ddb791919249effa0573883076681514787e4" } -dependencies = [ - { name = "filelock", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "geopandas", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "gymnasium", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "lxml", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "matplotlib", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "opencv-python-headless", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "panda3d", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "panda3d-gltf", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pandas", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pillow", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "progressbar", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "psutil", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pygame", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pygments", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "requests", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "scipy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "seaborn", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "shapely", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "tqdm", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "yapf", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, -] - -[[distribution]] +source = { git = "https://github.com/commaai/metadrive?rev=main#0dd67b8a924d65c5c263c63863c3e766850e0b66" } +dependencies = [ + { name = "filelock" }, + { name = "geopandas" }, + { name = "gymnasium" }, + { name = "lxml" }, + { name = "matplotlib" }, + { name = "numpy" }, + { name = "opencv-python-headless" }, + { name = "panda3d" }, + { name = "panda3d-gltf" }, + { name = "pandas" }, + { name = "pillow" }, + { name = "progressbar" }, + { name = "psutil" }, + { name = "pygame" }, + { name = "pygments" }, + { name = "pytest" }, + { name = "requests" }, + { name = "scipy" }, + { name = "seaborn" }, + { name = "shapely" }, + { name = "tqdm" }, + { name = "yapf" }, +] + +[[package]] name = "mkdocs" version = "1.6.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "click", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "click" }, { name = "colorama", marker = "platform_system == 'Windows'" }, - { name = "ghp-import", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "jinja2", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "markdown", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "markupsafe", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "mergedeep", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "mkdocs-get-deps", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pathspec", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyyaml", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyyaml-env-tag", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "watchdog", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "ghp-import" }, + { name = "jinja2" }, + { name = "markdown" }, + { name = "markupsafe" }, + { name = "mergedeep" }, + { name = "mkdocs-get-deps" }, + { name = "packaging" }, + { name = "pathspec" }, + { name = "pyyaml" }, + { name = "pyyaml-env-tag" }, + { name = "watchdog" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cc/6b/26b33cc8ad54e8bc0345cddc061c2c5c23e364de0ecd97969df23f95a673/mkdocs-1.6.0.tar.gz", hash = "sha256:a73f735824ef83a4f3bcb7a231dcab23f5a838f88b7efc54a0eef5fbdbc3c512", size = 3888392 } wheels = [ { url = "https://files.pythonhosted.org/packages/b8/c0/930dcf5a3e96b9c8e7ad15502603fc61d495479699e2d2c381e3d37294d1/mkdocs-1.6.0-py3-none-any.whl", hash = "sha256:1eb5cb7676b7d89323e62b56235010216319217d4af5ddc543a91beb8d125ea7", size = 3862264 }, ] -[[distribution]] +[[package]] name = "mkdocs-get-deps" version = "0.2.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "mergedeep", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "platformdirs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyyaml", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "mergedeep" }, + { name = "platformdirs" }, + { name = "pyyaml" }, ] sdist = { url = "https://files.pythonhosted.org/packages/98/f5/ed29cd50067784976f25ed0ed6fcd3c2ce9eb90650aa3b2796ddf7b6870b/mkdocs_get_deps-0.2.0.tar.gz", hash = "sha256:162b3d129c7fad9b19abfdcb9c1458a651628e4b1dea628ac68790fb3061c60c", size = 10239 } wheels = [ { url = "https://files.pythonhosted.org/packages/9f/d4/029f984e8d3f3b6b726bd33cafc473b75e9e44c0f7e80a5b29abc466bdea/mkdocs_get_deps-0.2.0-py3-none-any.whl", hash = "sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134", size = 9521 }, ] -[[distribution]] +[[package]] name = "mouseinfo" version = "0.1.3" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyperclip", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyperclip" }, { name = "python3-xlib", marker = "platform_system == 'Linux'" }, { name = "rubicon-objc", marker = "platform_system == 'Darwin'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/28/fa/b2ba8229b9381e8f6381c1dcae6f4159a7f72349e414ed19cfbbd1817173/MouseInfo-0.1.3.tar.gz", hash = "sha256:2c62fb8885062b8e520a3cce0a297c657adcc08c60952eb05bc8256ef6f7f6e7", size = 10850 } -[[distribution]] +[[package]] name = "mpmath" version = "1.3.0" source = { registry = "https://pypi.org/simple" } @@ -1167,34 +1200,34 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/43/e3/7d92a15f894aa0c9c4b49b8ee9ac9850d6e63b03c9c32c0367a13ae62209/mpmath-1.3.0-py3-none-any.whl", hash = "sha256:a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c", size = 536198 }, ] -[[distribution]] +[[package]] name = "msal" version = "1.30.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cryptography", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyjwt", extra = ["crypto"], marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "requests", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "cryptography" }, + { name = "pyjwt", extra = ["crypto"] }, + { name = "requests" }, ] sdist = { url = "https://files.pythonhosted.org/packages/03/ce/45b9af8f43fbbf34d15162e1e39ce34b675c234c56638277cc05562b6dbf/msal-1.30.0.tar.gz", hash = "sha256:b4bf00850092e465157d814efa24a18f788284c9a479491024d62903085ea2fb", size = 142510 } wheels = [ { url = "https://files.pythonhosted.org/packages/ab/82/8f19334da43b7ef72d995587991a446f140346d76edb96a2c1a2689588e9/msal-1.30.0-py3-none-any.whl", hash = "sha256:423872177410cb61683566dc3932db7a76f661a5d2f6f52f02a047f101e1c1de", size = 111760 }, ] -[[distribution]] +[[package]] name = "msal-extensions" version = "1.2.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "msal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "portalocker", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "msal" }, + { name = "portalocker" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2d/38/ad49272d0a5af95f7a0cb64a79bbd75c9c187f3b789385a143d8d537a5eb/msal_extensions-1.2.0.tar.gz", hash = "sha256:6f41b320bfd2933d631a215c91ca0dd3e67d84bd1a2f50ce917d5874ec646bef", size = 22391 } wheels = [ { url = "https://files.pythonhosted.org/packages/2c/69/314d887a01599669fb330da14e5c6ff5f138609e322812a942a74ef9b765/msal_extensions-1.2.0-py3-none-any.whl", hash = "sha256:cf5ba83a2113fa6dc011a254a72f1c223c88d7dfad74cc30617c4679a417704d", size = 19254 }, ] -[[distribution]] +[[package]] name = "multidict" version = "6.0.5" source = { registry = "https://pypi.org/simple" } @@ -1233,13 +1266,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fa/a2/17e1e23c6be0a916219c5292f509360c345b5fa6beeb50d743203c27532c/multidict-6.0.5-py3-none-any.whl", hash = "sha256:0d63c74e3d7ab26de115c49bffc92cc77ed23395303d496eae515d4204a625e7", size = 9729 }, ] -[[distribution]] +[[package]] name = "mypy" version = "1.11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "mypy-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "mypy-extensions" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b6/9c/a4b3bda53823439cf395db8ecdda6229a83f9bf201714a68a15190bb2919/mypy-1.11.1.tar.gz", hash = "sha256:f404a0b069709f18bbdb702eb3dcfe51910602995de00bd39cea3050b5772d08", size = 3078369 } wheels = [ @@ -1256,7 +1289,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f8/d4/4960d0df55f30a7625d9c3c9414dfd42f779caabae137ef73ffaed0c97b9/mypy-1.11.1-py3-none-any.whl", hash = "sha256:0624bdb940255d2dd24e829d99a13cfeb72e4e9031f9492148f410ed30bcab54", size = 2619257 }, ] -[[distribution]] +[[package]] name = "mypy-extensions" version = "1.0.0" source = { registry = "https://pypi.org/simple" } @@ -1265,7 +1298,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2a/e2/5d3f6ada4297caebe1a2add3b126fe800c96f56dbe5d1988a2cbe0b267aa/mypy_extensions-1.0.0-py3-none-any.whl", hash = "sha256:4392f6c0eb8a5668a69e23d168ffa70f0be9ccfd32b5cc2d26a34ae5b844552d", size = 4695 }, ] -[[distribution]] +[[package]] name = "natsort" version = "8.4.0" source = { registry = "https://pypi.org/simple" } @@ -1274,7 +1307,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ef/82/7a9d0550484a62c6da82858ee9419f3dd1ccc9aa1c26a1e43da3ecd20b0d/natsort-8.4.0-py3-none-any.whl", hash = "sha256:4732914fb471f56b5cce04d7bae6f164a592c7712e1c85f9ef585e197299521c", size = 38268 }, ] -[[distribution]] +[[package]] name = "numpy" version = "1.26.4" source = { registry = "https://pypi.org/simple" } @@ -1298,13 +1331,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/16/2e/86f24451c2d530c88daf997cb8d6ac622c1d40d19f5a031ed68a4b73a374/numpy-1.26.4-cp312-cp312-win_amd64.whl", hash = "sha256:08beddf13648eb95f8d867350f6a018a4be2e5ad54c8d8caed89ebca558b2818", size = 15517754 }, ] -[[distribution]] +[[package]] name = "onnx" version = "1.16.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "protobuf", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, + { name = "protobuf" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d8/83/09d7715612f72236b439eba6ebfecdaac59d99562dfc1d7a90dddb6168e1/onnx-1.16.2.tar.gz", hash = "sha256:b33a282b038813c4b69e73ea65c2909768e8dd6cc10619b70632335daf094646", size = 12308861 } wheels = [ @@ -1320,17 +1353,17 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2b/66/121875d593a51ffd7a35315855c0e09ceca43c0bfe0e98af72053cc83682/onnx-1.16.2-cp312-cp312-win_amd64.whl", hash = "sha256:080b19b0bd2b5536b4c61812464fe495758d6c9cfed3fdd3f20516e616212bee", size = 14441282 }, ] -[[distribution]] +[[package]] name = "onnxruntime" version = "1.18.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "coloredlogs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "flatbuffers", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "protobuf", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "sympy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "coloredlogs" }, + { name = "flatbuffers" }, + { name = "numpy" }, + { name = "packaging" }, + { name = "protobuf" }, + { name = "sympy" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/d7/ae/e257a5ffa4ef84e51255a38b62b4fdb538d92455e1f0f0ad056074f89c94/onnxruntime-1.18.1-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:f26582882f2dc581b809cfa41a125ba71ad9e715738ec6402418df356969774a", size = 15892594 }, @@ -1345,17 +1378,17 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/80/62/3f54fd70511e004869a2bc5c4ba4303a5b51b625ff81bd989c35d1d8086a/onnxruntime-1.18.1-cp312-cp312-win_amd64.whl", hash = "sha256:ad93c560b1c38c27c0275ffd15cd7f45b3ad3fc96653c09ce2931179982ff204", size = 5584630 }, ] -[[distribution]] +[[package]] name = "onnxruntime-gpu" version = "1.18.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "coloredlogs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "flatbuffers", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "protobuf", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "sympy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "coloredlogs" }, + { name = "flatbuffers" }, + { name = "numpy" }, + { name = "packaging" }, + { name = "protobuf" }, + { name = "sympy" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/92/2e/5c6a3c94a8e4794a0ad1ba00f5b86c89673f271f43c77f537a90db4472c0/onnxruntime_gpu-1.18.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:af2d3ee6fba72b57abf6f379b8aca30ee773959d4346271e7d92557dd5cf2901", size = 200794895 }, @@ -1364,12 +1397,12 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/31/f0/84034a7592937f02ca3c671e50b767f86a721959619635fe40ffa14031e0/onnxruntime_gpu-1.18.1-cp312-cp312-win_amd64.whl", hash = "sha256:3f2ab38a62350965f5007111728410b3ef25213104dd1e7d61ecc158002ea3f5", size = 157671367 }, ] -[[distribution]] +[[package]] name = "opencv-python-headless" version = "4.10.0.84" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2f/7e/d20f68a5f1487adf19d74378d349932a386b1ece3be9be9915e5986db468/opencv-python-headless-4.10.0.84.tar.gz", hash = "sha256:f2017c6101d7c2ef8d7bc3b414c37ff7f54d64413a1847d89970b6b7069b4e1a", size = 95117755 } wheels = [ @@ -1381,94 +1414,170 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/26/d0/22f68eb23eea053a31655960f133c0be9726c6a881547e6e9e7e2a946c4f/opencv_python_headless-4.10.0.84-cp37-abi3-win_amd64.whl", hash = "sha256:afcf28bd1209dd58810d33defb622b325d3cbe49dcd7a43a902982c33e5fad05", size = 38754031 }, ] -[[distribution]] +[[package]] name = "openpilot" version = "0.1.0" source = { editable = "." } dependencies = [ - { name = "aiohttp", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "aiortc", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "casadi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cffi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "crcmod", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "cython", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "future-fstrings", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "json-rpc", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "libusb1", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "onnx", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "aiohttp" }, + { name = "aiortc" }, + { name = "casadi" }, + { name = "cffi" }, + { name = "crcmod" }, + { name = "cython" }, + { name = "future-fstrings" }, + { name = "json-rpc" }, + { name = "libusb1" }, + { name = "numpy" }, + { name = "onnx" }, { name = "onnxruntime", marker = "platform_machine == 'aarch64' and platform_system == 'Linux'" }, { name = "onnxruntime-gpu", marker = "platform_machine == 'x86_64' and platform_system == 'Linux'" }, - { name = "psutil", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyaudio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pycapnp", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pycryptodome", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyjwt", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyserial", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyzmq", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "requests", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "scons", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "sentry-sdk", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "setproctitle", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "setuptools", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "smbus2", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "sounddevice", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "psutil" }, + { name = "pyaudio" }, + { name = "pycapnp" }, + { name = "pycryptodome" }, + { name = "pyjwt" }, + { name = "pyserial" }, + { name = "pyzmq" }, + { name = "requests" }, + { name = "scons" }, + { name = "sentry-sdk" }, + { name = "setproctitle" }, + { name = "setuptools" }, + { name = "smbus2" }, + { name = "sounddevice" }, { name = "spidev", marker = "platform_system == 'Linux'" }, - { name = "sympy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "tqdm", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "websocket-client", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "zstandard", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "sympy" }, + { name = "tqdm" }, + { name = "websocket-client" }, + { name = "zstandard" }, ] -[distribution.optional-dependencies] +[package.optional-dependencies] dev = [ - { name = "av", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "azure-identity", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "azure-storage-blob", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "dictdiffer", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "flaky", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "inputs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "lru-dict", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "matplotlib", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "av" }, + { name = "azure-identity" }, + { name = "azure-storage-blob" }, + { name = "dictdiffer" }, + { name = "flaky" }, + { name = "inputs" }, + { name = "lru-dict" }, + { name = "matplotlib" }, { name = "metadrive-simulator", marker = "platform_machine != 'aarch64'" }, - { name = "parameterized", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyautogui", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "parameterized" }, + { name = "pyautogui" }, { name = "pyopencl", marker = "platform_machine != 'aarch64'" }, - { name = "pyprof2calltree", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyprof2calltree" }, { name = "pyqt5", marker = "platform_machine == 'x86_64'" }, { name = "pytools", marker = "platform_machine != 'aarch64'" }, - { name = "pywinctl", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "rerun-sdk", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "tabulate", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "types-requests", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "types-tabulate", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pywinctl" }, + { name = "rerun-sdk" }, + { name = "tabulate" }, + { name = "types-requests" }, + { name = "types-tabulate" }, ] docs = [ - { name = "jinja2", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "mkdocs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "natsort", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "jinja2" }, + { name = "mkdocs" }, + { name = "natsort" }, ] testing = [ - { name = "codespell", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "coverage", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "hypothesis", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "import-linter", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "mypy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pre-commit-hooks", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-asyncio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-cov", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-cpp", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-mock", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-randomly", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-repeat", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-subtests", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-timeout", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest-xdist", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "ruff", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, -] - -[[distribution]] + { name = "codespell" }, + { name = "coverage" }, + { name = "hypothesis" }, + { name = "import-linter" }, + { name = "mypy" }, + { name = "pre-commit-hooks" }, + { name = "pytest" }, + { name = "pytest-asyncio" }, + { name = "pytest-cov" }, + { name = "pytest-cpp" }, + { name = "pytest-mock" }, + { name = "pytest-randomly" }, + { name = "pytest-repeat" }, + { name = "pytest-subtests" }, + { name = "pytest-timeout" }, + { name = "pytest-xdist" }, + { name = "ruff" }, +] + +[package.metadata] +requires-dist = [ + { name = "aiohttp" }, + { name = "aiortc" }, + { name = "av", marker = "extra == 'dev'" }, + { name = "azure-identity", marker = "extra == 'dev'" }, + { name = "azure-storage-blob", marker = "extra == 'dev'" }, + { name = "casadi", specifier = ">=3.6.6" }, + { name = "cffi" }, + { name = "codespell", marker = "extra == 'testing'" }, + { name = "coverage", marker = "extra == 'testing'" }, + { name = "crcmod" }, + { name = "cython" }, + { name = "dictdiffer", marker = "extra == 'dev'" }, + { name = "flaky", marker = "extra == 'dev'" }, + { name = "future-fstrings" }, + { name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" }, + { name = "import-linter", marker = "extra == 'testing'" }, + { name = "inputs", marker = "extra == 'dev'" }, + { name = "jinja2", marker = "extra == 'docs'" }, + { name = "json-rpc" }, + { name = "libusb1" }, + { name = "lru-dict", marker = "extra == 'dev'" }, + { name = "matplotlib", marker = "extra == 'dev'" }, + { name = "metadrive-simulator", marker = "platform_machine != 'aarch64' and extra == 'dev'", git = "https://github.com/commaai/metadrive?rev=main" }, + { name = "mkdocs", marker = "extra == 'docs'" }, + { name = "mypy", marker = "extra == 'testing'" }, + { name = "natsort", marker = "extra == 'docs'" }, + { name = "numpy", specifier = "<2.0.0" }, + { name = "onnx", specifier = ">=1.14.0" }, + { name = "onnxruntime", marker = "platform_machine == 'aarch64' and platform_system == 'Linux'", specifier = ">=1.16.3" }, + { name = "onnxruntime-gpu", marker = "platform_machine == 'x86_64' and platform_system == 'Linux'", specifier = ">=1.16.3" }, + { name = "parameterized", marker = "extra == 'dev'", specifier = ">=0.8,<0.9" }, + { name = "pre-commit-hooks", marker = "extra == 'testing'" }, + { name = "psutil" }, + { name = "pyaudio" }, + { name = "pyautogui", marker = "extra == 'dev'" }, + { name = "pycapnp" }, + { name = "pycryptodome" }, + { name = "pyjwt" }, + { name = "pyopencl", marker = "platform_machine != 'aarch64' and extra == 'dev'" }, + { name = "pyprof2calltree", marker = "extra == 'dev'" }, + { name = "pyqt5", marker = "platform_machine == 'x86_64' and extra == 'dev'", specifier = "==5.15.2" }, + { name = "pyserial" }, + { name = "pytest", marker = "extra == 'testing'" }, + { name = "pytest-asyncio", marker = "extra == 'testing'" }, + { name = "pytest-cov", marker = "extra == 'testing'" }, + { name = "pytest-cpp", marker = "extra == 'testing'" }, + { name = "pytest-mock", marker = "extra == 'testing'" }, + { name = "pytest-randomly", marker = "extra == 'testing'" }, + { name = "pytest-repeat", marker = "extra == 'testing'" }, + { name = "pytest-subtests", marker = "extra == 'testing'" }, + { name = "pytest-timeout", marker = "extra == 'testing'" }, + { name = "pytest-xdist", marker = "extra == 'testing'" }, + { name = "pytools", marker = "platform_machine != 'aarch64' and extra == 'dev'", specifier = "<2024.1.11" }, + { name = "pywinctl", marker = "extra == 'dev'" }, + { name = "pyzmq" }, + { name = "requests" }, + { name = "rerun-sdk", marker = "extra == 'dev'", specifier = ">=0.18" }, + { name = "ruff", marker = "extra == 'testing'" }, + { name = "scons" }, + { name = "sentry-sdk" }, + { name = "setproctitle" }, + { name = "setuptools" }, + { name = "smbus2" }, + { name = "sounddevice" }, + { name = "spidev", marker = "platform_system == 'Linux'" }, + { name = "sympy" }, + { name = "tabulate", marker = "extra == 'dev'" }, + { name = "tqdm" }, + { name = "types-requests", marker = "extra == 'dev'" }, + { name = "types-tabulate", marker = "extra == 'dev'" }, + { name = "websocket-client" }, + { name = "zstandard" }, +] + +[[package]] name = "packaging" version = "24.1" source = { registry = "https://pypi.org/simple" } @@ -1477,7 +1586,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/08/aa/cc0199a5f0ad350994d660967a8efb233fe0416e4639146c089643407ce6/packaging-24.1-py3-none-any.whl", hash = "sha256:5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124", size = 53985 }, ] -[[distribution]] +[[package]] name = "panda3d" version = "1.10.14" source = { registry = "https://pypi.org/simple" } @@ -1495,41 +1604,41 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/74/bb/cb57563855da994614a33f57bd5691fbcd69f12e5ccddd30d387d0be287f/panda3d-1.10.14-cp312-cp312-win_amd64.whl", hash = "sha256:a5f2defd822d38848f8ae1956115adcb6cc7f464f03a67e73681cc72df125ef4", size = 64893222 }, ] -[[distribution]] +[[package]] name = "panda3d-gltf" version = "0.13" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "panda3d", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "panda3d-simplepbr", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "panda3d" }, + { name = "panda3d-simplepbr" }, ] sdist = { url = "https://files.pythonhosted.org/packages/07/7f/9f18fc3fa843a080acb891af6bcc12262e7bdf1d194a530f7042bebfc81f/panda3d-gltf-0.13.tar.gz", hash = "sha256:d06d373bdd91cf530909b669f43080e599463bbf6d3ef00c3558bad6c6b19675", size = 25573 } wheels = [ { url = "https://files.pythonhosted.org/packages/70/94/98ed1f81ca0f5daf6de80533805cc1e98ac162abe4e3e1d382caa7ba5c3c/panda3d_gltf-0.13-py3-none-any.whl", hash = "sha256:02d1a980f447bb1895ff4b48c667f289ba78f07a28ef308d8839b665a621efe2", size = 25568 }, ] -[[distribution]] +[[package]] name = "panda3d-simplepbr" version = "0.12.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "panda3d", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "panda3d" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b1/af/505608eef09d7f9b822e69dc7631cd14102650b8fe1b6f60d9562d2788d9/panda3d-simplepbr-0.12.0.tar.gz", hash = "sha256:c71d490afeeb3a90455dcfde1d30c41f321a38742a97d18834e5c31016331ed5", size = 1929980 } wheels = [ { url = "https://files.pythonhosted.org/packages/46/4c/926e1cf17abfb1d91e12bf38e653cacf10e30c5030e37f9078f0f41aaf40/panda3d_simplepbr-0.12.0-py3-none-any.whl", hash = "sha256:6c43d1990ff07840cf1c557561d6122fd1250d8e76aacf227b61c3789149bcf9", size = 2458121 }, ] -[[distribution]] +[[package]] name = "pandas" version = "2.2.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12'" }, - { name = "python-dateutil", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "tzdata", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, + { name = "python-dateutil" }, + { name = "pytz" }, + { name = "tzdata" }, ] sdist = { url = "https://files.pythonhosted.org/packages/88/d9/ecf715f34c73ccb1d8ceb82fc01cd1028a65a5f6dbc57bfa6ea155119058/pandas-2.2.2.tar.gz", hash = "sha256:9e79019aba43cb4fda9e4d983f8e88ca0373adbb697ae9c6c43093218de28b54", size = 4398391 } wheels = [ @@ -1549,7 +1658,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/22/a5/a0b255295406ed54269814bc93723cfd1a0da63fb9aaf99e1364f07923e5/pandas-2.2.2-cp312-cp312-win_amd64.whl", hash = "sha256:d187d355ecec3629624fccb01d104da7d7f391db0311145817525281e2804d23", size = 11498828 }, ] -[[distribution]] +[[package]] name = "parameterized" version = "0.8.1" source = { registry = "https://pypi.org/simple" } @@ -1558,7 +1667,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/31/13/fe468c8c7400a8eca204e6e160a29bf7dcd45a76e20f1c030f3eaa690d93/parameterized-0.8.1-py2.py3-none-any.whl", hash = "sha256:9cbb0b69a03e8695d68b3399a8a5825200976536fe1cb79db60ed6a4c8c9efe9", size = 26354 }, ] -[[distribution]] +[[package]] name = "pathspec" version = "0.12.1" source = { registry = "https://pypi.org/simple" } @@ -1567,7 +1676,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/cc/20/ff623b09d963f88bfde16306a54e12ee5ea43e9b597108672ff3a408aad6/pathspec-0.12.1-py3-none-any.whl", hash = "sha256:a0d503e138a4c123b27490a4f7beda6a01c6f288df0e4a8b79c7eb0dc7b4cc08", size = 31191 }, ] -[[distribution]] +[[package]] name = "pillow" version = "10.4.0" source = { registry = "https://pypi.org/simple" } @@ -1608,7 +1717,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/48/2c/2e0a52890f269435eee38b21c8218e102c621fe8d8df8b9dd06fabf879ba/pillow-10.4.0-cp313-cp313-win_arm64.whl", hash = "sha256:5b001114dd152cfd6b23befeb28d7aee43553e2402c9f159807bf55f33af8a8d", size = 2243375 }, ] -[[distribution]] +[[package]] name = "platformdirs" version = "4.2.2" source = { registry = "https://pypi.org/simple" } @@ -1617,7 +1726,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/68/13/2aa1f0e1364feb2c9ef45302f387ac0bd81484e9c9a4c5688a322fbdfd08/platformdirs-4.2.2-py3-none-any.whl", hash = "sha256:2d7a1657e36a80ea911db832a8a6ece5ee53d8de21edd5cc5879af6530b1bfee", size = 18146 }, ] -[[distribution]] +[[package]] name = "pluggy" version = "1.5.0" source = { registry = "https://pypi.org/simple" } @@ -1626,7 +1735,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/88/5f/e351af9a41f866ac3f1fac4ca0613908d9a41741cfcf2228f4ad853b697d/pluggy-1.5.0-py3-none-any.whl", hash = "sha256:44e1ad92c8ca002de6377e165f3e0f1be63266ab4d554740532335b9d75ea669", size = 20556 }, ] -[[distribution]] +[[package]] name = "portalocker" version = "2.10.1" source = { registry = "https://pypi.org/simple" } @@ -1638,25 +1747,25 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9b/fb/a70a4214956182e0d7a9099ab17d50bfcba1056188e9b14f35b9e2b62a0d/portalocker-2.10.1-py3-none-any.whl", hash = "sha256:53a5984ebc86a025552264b459b46a2086e269b21823cb572f8f28ee759e45bf", size = 18423 }, ] -[[distribution]] +[[package]] name = "pre-commit-hooks" version = "4.6.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "ruamel-yaml", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "ruamel-yaml" }, ] sdist = { url = "https://files.pythonhosted.org/packages/83/0d/b4e97cd99b26c0cd8265c9f19ee7e55248142f0c9955e4d119de96fa4a13/pre_commit_hooks-4.6.0.tar.gz", hash = "sha256:eb1f43ee67869cd41b4c59017fad4a0f9d4d61201d163f2135535aaf65035a2b", size = 29579 } wheels = [ { url = "https://files.pythonhosted.org/packages/95/d8/d09b270248bc2441f966dd094a3de8ae813112d2687036f621202bdef80b/pre_commit_hooks-4.6.0-py2.py3-none-any.whl", hash = "sha256:a69199e6a2d45ec59c1020a81ca1549abddc2afb798276d9a0d951752d6abbfe", size = 41193 }, ] -[[distribution]] +[[package]] name = "progressbar" version = "2.5" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/a3/a6/b8e451f6cff1c99b4747a2f7235aa904d2d49e8e1464e0b798272aa84358/progressbar-2.5.tar.gz", hash = "sha256:5d81cb529da2e223b53962afd6c8ca0f05c6670e40309a7219eacc36af9b6c63", size = 10046 } -[[distribution]] +[[package]] name = "protobuf" version = "5.27.3" source = { registry = "https://pypi.org/simple" } @@ -1670,7 +1779,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e1/94/d77bd282d3d53155147166c2bbd156f540009b0d7be24330f76286668b90/protobuf-5.27.3-py3-none-any.whl", hash = "sha256:8572c6533e544ebf6899c360e91d6bcbbee2549251643d32c52cf8a5de295ba5", size = 164778 }, ] -[[distribution]] +[[package]] name = "psutil" version = "6.0.0" source = { registry = "https://pypi.org/simple" } @@ -1687,12 +1796,12 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7c/06/63872a64c312a24fb9b4af123ee7007a306617da63ff13bcc1432386ead7/psutil-6.0.0-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:ffe7fc9b6b36beadc8c322f84e1caff51e8703b88eee1da46d1e3a6ae11b4fd0", size = 251988 }, ] -[[distribution]] +[[package]] name = "pyarrow" version = "17.0.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/27/4e/ea6d43f324169f8aec0e57569443a38bab4b398d09769ca64f7b4d467de3/pyarrow-17.0.0.tar.gz", hash = "sha256:4beca9521ed2c0921c1023e68d097d0299b62c362639ea315572a58f3f50fd28", size = 1112479 } wheels = [ @@ -1712,7 +1821,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ae/49/baafe2a964f663413be3bd1cf5c45ed98c5e42e804e2328e18f4570027c1/pyarrow-17.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:392bc9feabc647338e6c89267635e111d71edad5fcffba204425a7c8d13610d7", size = 25099235 }, ] -[[distribution]] +[[package]] name = "pyaudio" version = "0.2.14" source = { registry = "https://pypi.org/simple" } @@ -1724,23 +1833,23 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b0/6a/d25812e5f79f06285767ec607b39149d02aa3b31d50c2269768f48768930/PyAudio-0.2.14-cp312-cp312-win_amd64.whl", hash = "sha256:12f2f1ba04e06ff95d80700a78967897a489c05e093e3bffa05a84ed9c0a7fa3", size = 164126 }, ] -[[distribution]] +[[package]] name = "pyautogui" version = "0.9.54" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "mouseinfo", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pygetwindow", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pymsgbox", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "mouseinfo" }, + { name = "pygetwindow" }, + { name = "pymsgbox" }, { name = "pyobjc-core", marker = "platform_system == 'Darwin'" }, { name = "pyobjc-framework-quartz", marker = "platform_system == 'Darwin'" }, - { name = "pyscreeze", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyscreeze" }, { name = "python3-xlib", marker = "platform_system == 'Linux'" }, - { name = "pytweening", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pytweening" }, ] sdist = { url = "https://files.pythonhosted.org/packages/65/ff/cdae0a8c2118a0de74b6cf4cbcdcaf8fd25857e6c3f205ce4b1794b27814/PyAutoGUI-0.9.54.tar.gz", hash = "sha256:dd1d29e8fd118941cb193f74df57e5c6ff8e9253b99c7b04f39cfc69f3ae04b2", size = 61236 } -[[distribution]] +[[package]] name = "pycapnp" version = "2.0.0" source = { registry = "https://pypi.org/simple" } @@ -1776,7 +1885,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3f/70/a71108ee9d4db9a027b665a2c383202407207174f1956195d5be45aca705/pycapnp-2.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:b8b03000769b29b36a8810f458b931f0f706f42027ee6676821eff28092d7734", size = 1135121 }, ] -[[distribution]] +[[package]] name = "pycparser" version = "2.22" source = { registry = "https://pypi.org/simple" } @@ -1785,7 +1894,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/13/a3/a812df4e2dd5696d1f351d58b8fe16a405b234ad2886a0dab9183fb78109/pycparser-2.22-py3-none-any.whl", hash = "sha256:c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc", size = 117552 }, ] -[[distribution]] +[[package]] name = "pycryptodome" version = "3.20.0" source = { registry = "https://pypi.org/simple" } @@ -1805,19 +1914,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/68/9a/88d984405b087e8c8dd9a9d4c81a6fa675454e5fcf2ae01d9553b3128637/pycryptodome-3.20.0-pp27-pypy_73-win32.whl", hash = "sha256:ec1f93feb3bb93380ab0ebf8b859e8e5678c0f010d2d78367cf6bc30bfeb148e", size = 1708332 }, ] -[[distribution]] +[[package]] name = "pyee" version = "11.1.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "typing-extensions" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f7/22/b4c7f3d9579204a014c4eda0e019e6bfe56af52a96cacc82004b60eec079/pyee-11.1.0.tar.gz", hash = "sha256:b53af98f6990c810edd9b56b87791021a8f54fd13db4edd1142438d44ba2263f", size = 29806 } wheels = [ { url = "https://files.pythonhosted.org/packages/16/cc/5cea8a0a0d3deb90b5a0d39ad1a6a1ccaa40a9ea86d793eb8a49d32a6ed0/pyee-11.1.0-py3-none-any.whl", hash = "sha256:5d346a7d0f861a4b2e6c47960295bd895f816725b27d656181947346be98d7c1", size = 15263 }, ] -[[distribution]] +[[package]] name = "pygame" version = "2.6.0" source = { registry = "https://pypi.org/simple" } @@ -1839,16 +1948,16 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c2/a2/7a4e02e5833e7391ca4e4e08bdda0bdab6672d8ce3ddee433d50297135ec/pygame-2.6.0-cp312-cp312-win_amd64.whl", hash = "sha256:1c429824b1f881a7a5ce3b5c2014d3d182aa45a22cea33c8347a3971a5446907", size = 10754182 }, ] -[[distribution]] +[[package]] name = "pygetwindow" version = "0.0.9" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyrect", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyrect" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e1/70/c7a4f46dbf06048c6d57d9489b8e0f9c4c3d36b7479f03c5ca97eaa2541d/PyGetWindow-0.0.9.tar.gz", hash = "sha256:17894355e7d2b305cd832d717708384017c1698a90ce24f6f7fbf0242dd0a688", size = 9699 } -[[distribution]] +[[package]] name = "pygments" version = "2.18.0" source = { registry = "https://pypi.org/simple" } @@ -1857,7 +1966,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f7/3f/01c8b82017c199075f8f788d0d906b9ffbbc5a47dc9918a945e13d5a2bda/pygments-2.18.0-py3-none-any.whl", hash = "sha256:b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a", size = 1205513 }, ] -[[distribution]] +[[package]] name = "pyjwt" version = "2.9.0" source = { registry = "https://pypi.org/simple" } @@ -1866,17 +1975,17 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/79/84/0fdf9b18ba31d69877bd39c9cd6052b47f3761e9910c15de788e519f079f/PyJWT-2.9.0-py3-none-any.whl", hash = "sha256:3b02fb0f44517787776cf48f2ae25d8e14f300e6d7545a4315cee571a415e850", size = 22344 }, ] -[distribution.optional-dependencies] +[package.optional-dependencies] crypto = [ - { name = "cryptography", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "cryptography" }, ] -[[distribution]] +[[package]] name = "pylibsrtp" version = "0.10.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cffi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "cffi" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6b/ae/c95199144eed954976223bdce3f94564eb6c43567111aff8048a26a429bd/pylibsrtp-0.10.0.tar.gz", hash = "sha256:d8001912d7f51bd05b4ea3551747930631777fd37892cf3bfe0e541a742e699f", size = 10557 } wheels = [ @@ -1889,7 +1998,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/4c/31/85a58625edc0b6967fe0904c9d89d019bcece3f3e3bf775b9151a8cf9d0d/pylibsrtp-0.10.0-cp38-abi3-win_amd64.whl", hash = "sha256:cd965d4b0e9a77b362526cab119f4d9ce39b83f1f20f46c6af8e694b86fa19a7", size = 1448840 }, ] -[[distribution]] +[[package]] name = "pymonctl" version = "0.92" source = { registry = "https://pypi.org/simple" } @@ -1898,37 +2007,37 @@ dependencies = [ { name = "pyobjc", marker = "sys_platform == 'darwin'" }, { name = "python-xlib", marker = "sys_platform == 'linux'" }, { name = "pywin32", marker = "sys_platform == 'win32'" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "typing-extensions" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/2d/13/076a20da28b82be281f7e43e16d9da0f545090f5d14b2125699232b9feba/PyMonCtl-0.92-py3-none-any.whl", hash = "sha256:2495d8dab78f9a7dbce37e74543e60b8bd404a35c3108935697dda7768611b5a", size = 45945 }, ] -[[distribution]] +[[package]] name = "pymsgbox" version = "1.0.9" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/7d/ff/4c6f31a4f08979f12a663f2aeb6c8b765d3bd592e66eaaac445f547bb875/PyMsgBox-1.0.9.tar.gz", hash = "sha256:2194227de8bff7a3d6da541848705a155dcbb2a06ee120d9f280a1d7f51263ff", size = 18829 } -[[distribution]] +[[package]] name = "pyobjc" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, { name = "pyobjc-framework-accessibility", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-accounts", marker = "platform_release >= '12.0'" }, - { name = "pyobjc-framework-addressbook", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-addressbook" }, { name = "pyobjc-framework-adservices", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-adsupport", marker = "platform_release >= '18.0'" }, - { name = "pyobjc-framework-applescriptkit", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-applescriptkit" }, { name = "pyobjc-framework-applescriptobjc", marker = "platform_release >= '10.0'" }, - { name = "pyobjc-framework-applicationservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-applicationservices" }, { name = "pyobjc-framework-apptrackingtransparency", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-audiovideobridging", marker = "platform_release >= '12.0'" }, { name = "pyobjc-framework-authenticationservices", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-automaticassessmentconfiguration", marker = "platform_release >= '19.0'" }, - { name = "pyobjc-framework-automator", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-automator" }, { name = "pyobjc-framework-avfoundation", marker = "platform_release >= '11.0'" }, { name = "pyobjc-framework-avkit", marker = "platform_release >= '13.0'" }, { name = "pyobjc-framework-avrouting", marker = "platform_release >= '22.0'" }, @@ -1937,40 +2046,40 @@ dependencies = [ { name = "pyobjc-framework-businesschat", marker = "platform_release >= '18.0'" }, { name = "pyobjc-framework-calendarstore", marker = "platform_release >= '9.0'" }, { name = "pyobjc-framework-callkit", marker = "platform_release >= '20.0'" }, - { name = "pyobjc-framework-cfnetwork", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-cfnetwork" }, { name = "pyobjc-framework-cinematic", marker = "platform_release >= '23.0'" }, { name = "pyobjc-framework-classkit", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-cloudkit", marker = "platform_release >= '14.0'" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-cocoa" }, { name = "pyobjc-framework-collaboration", marker = "platform_release >= '9.0'" }, { name = "pyobjc-framework-colorsync", marker = "platform_release >= '17.0'" }, { name = "pyobjc-framework-contacts", marker = "platform_release >= '15.0'" }, { name = "pyobjc-framework-contactsui", marker = "platform_release >= '15.0'" }, - { name = "pyobjc-framework-coreaudio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreaudiokit", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coreaudiokit" }, { name = "pyobjc-framework-corebluetooth", marker = "platform_release >= '14.0'" }, - { name = "pyobjc-framework-coredata", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-coredata" }, { name = "pyobjc-framework-corehaptics", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-corelocation", marker = "platform_release >= '10.0'" }, { name = "pyobjc-framework-coremedia", marker = "platform_release >= '11.0'" }, { name = "pyobjc-framework-coremediaio", marker = "platform_release >= '11.0'" }, - { name = "pyobjc-framework-coremidi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-coremidi" }, { name = "pyobjc-framework-coreml", marker = "platform_release >= '17.0'" }, { name = "pyobjc-framework-coremotion", marker = "platform_release >= '19.0'" }, - { name = "pyobjc-framework-coreservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-coreservices" }, { name = "pyobjc-framework-corespotlight", marker = "platform_release >= '17.0'" }, - { name = "pyobjc-framework-coretext", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-coretext" }, { name = "pyobjc-framework-corewlan", marker = "platform_release >= '10.0'" }, { name = "pyobjc-framework-cryptotokenkit", marker = "platform_release >= '14.0'" }, { name = "pyobjc-framework-datadetection", marker = "platform_release >= '21.0'" }, { name = "pyobjc-framework-devicecheck", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-dictionaryservices", marker = "platform_release >= '9.0'" }, - { name = "pyobjc-framework-discrecording", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-discrecordingui", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-diskarbitration", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-dvdplayback", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-discrecording" }, + { name = "pyobjc-framework-discrecordingui" }, + { name = "pyobjc-framework-diskarbitration" }, + { name = "pyobjc-framework-dvdplayback" }, { name = "pyobjc-framework-eventkit", marker = "platform_release >= '12.0'" }, - { name = "pyobjc-framework-exceptionhandling", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-exceptionhandling" }, { name = "pyobjc-framework-executionpolicy", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-extensionkit", marker = "platform_release >= '22.0'" }, { name = "pyobjc-framework-externalaccessory", marker = "platform_release >= '17.0'" }, @@ -1985,17 +2094,17 @@ dependencies = [ { name = "pyobjc-framework-healthkit", marker = "platform_release >= '22.0'" }, { name = "pyobjc-framework-imagecapturecore", marker = "platform_release >= '10.0'" }, { name = "pyobjc-framework-inputmethodkit", marker = "platform_release >= '9.0'" }, - { name = "pyobjc-framework-installerplugins", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-installerplugins" }, { name = "pyobjc-framework-instantmessage", marker = "platform_release >= '9.0'" }, { name = "pyobjc-framework-intents", marker = "platform_release >= '16.0'" }, { name = "pyobjc-framework-intentsui", marker = "platform_release >= '21.0'" }, - { name = "pyobjc-framework-iobluetooth", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-iobluetoothui", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-iobluetooth" }, + { name = "pyobjc-framework-iobluetoothui" }, { name = "pyobjc-framework-iosurface", marker = "platform_release >= '10.0'" }, { name = "pyobjc-framework-ituneslibrary", marker = "platform_release >= '10.0'" }, { name = "pyobjc-framework-kernelmanagement", marker = "platform_release >= '20.0'" }, - { name = "pyobjc-framework-latentsemanticmapping", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-launchservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-latentsemanticmapping" }, + { name = "pyobjc-framework-launchservices" }, { name = "pyobjc-framework-libdispatch", marker = "platform_release >= '12.0'" }, { name = "pyobjc-framework-libxpc", marker = "platform_release >= '12.0'" }, { name = "pyobjc-framework-linkpresentation", marker = "platform_release >= '19.0'" }, @@ -2022,30 +2131,29 @@ dependencies = [ { name = "pyobjc-framework-networkextension", marker = "platform_release >= '15.0'" }, { name = "pyobjc-framework-notificationcenter", marker = "platform_release >= '14.0'" }, { name = "pyobjc-framework-opendirectory", marker = "platform_release >= '10.0'" }, - { name = "pyobjc-framework-osakit", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-osakit" }, { name = "pyobjc-framework-oslog", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-passkit", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-pencilkit", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-phase", marker = "platform_release >= '21.0'" }, { name = "pyobjc-framework-photos", marker = "platform_release >= '15.0'" }, { name = "pyobjc-framework-photosui", marker = "platform_release >= '15.0'" }, - { name = "pyobjc-framework-preferencepanes", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-pubsub", marker = "platform_release >= '9.0' and platform_release < '18.0'" }, + { name = "pyobjc-framework-preferencepanes" }, { name = "pyobjc-framework-pushkit", marker = "platform_release >= '19.0'" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-quartz" }, { name = "pyobjc-framework-quicklookthumbnailing", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-replaykit", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-safariservices", marker = "platform_release >= '16.0'" }, { name = "pyobjc-framework-safetykit", marker = "platform_release >= '22.0'" }, { name = "pyobjc-framework-scenekit", marker = "platform_release >= '11.0'" }, { name = "pyobjc-framework-screencapturekit", marker = "platform_release >= '21.4'" }, - { name = "pyobjc-framework-screensaver", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-screensaver" }, { name = "pyobjc-framework-screentime", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-scriptingbridge", marker = "platform_release >= '9.0'" }, - { name = "pyobjc-framework-searchkit", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-security", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-securityfoundation", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-securityinterface", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-searchkit" }, + { name = "pyobjc-framework-security" }, + { name = "pyobjc-framework-securityfoundation" }, + { name = "pyobjc-framework-securityinterface" }, { name = "pyobjc-framework-sensitivecontentanalysis", marker = "platform_release >= '23.0'" }, { name = "pyobjc-framework-servicemanagement", marker = "platform_release >= '10.0'" }, { name = "pyobjc-framework-sharedwithyou", marker = "platform_release >= '22.0'" }, @@ -2057,8 +2165,8 @@ dependencies = [ { name = "pyobjc-framework-spritekit", marker = "platform_release >= '13.0'" }, { name = "pyobjc-framework-storekit", marker = "platform_release >= '11.0'" }, { name = "pyobjc-framework-symbols", marker = "platform_release >= '23.0'" }, - { name = "pyobjc-framework-syncservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-systemconfiguration", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-syncservices" }, + { name = "pyobjc-framework-systemconfiguration" }, { name = "pyobjc-framework-systemextensions", marker = "platform_release >= '19.0'" }, { name = "pyobjc-framework-threadnetwork", marker = "platform_release >= '22.0'" }, { name = "pyobjc-framework-uniformtypeidentifiers", marker = "platform_release >= '20.0'" }, @@ -2068,14 +2176,14 @@ dependencies = [ { name = "pyobjc-framework-videotoolbox", marker = "platform_release >= '12.0'" }, { name = "pyobjc-framework-virtualization", marker = "platform_release >= '20.0'" }, { name = "pyobjc-framework-vision", marker = "platform_release >= '17.0'" }, - { name = "pyobjc-framework-webkit", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-framework-webkit" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e0/20/722e33f62631370c1475d773cadf4290d3c6f3a0e9d025fa6e2528270eaa/pyobjc-10.3.1.tar.gz", hash = "sha256:476dd5c72394e4cfcdac6dfd756839011a0159353247f45e3e07cc0b3536c9d4", size = 10975 } wheels = [ { url = "https://files.pythonhosted.org/packages/cb/a5/4b9ed66894d804dc57c13b7fdb8f65ed831f13514216ce736e1455dfe214/pyobjc-10.3.1-py3-none-any.whl", hash = "sha256:dfa9ff44a353b9d0bf1245c25c94d1eee6d0cb26d9c5433bbcd67a265f7654ae", size = 4050 }, ] -[[distribution]] +[[package]] name = "pyobjc-core" version = "10.3.1" source = { registry = "https://pypi.org/simple" } @@ -2086,14 +2194,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2e/8b/341571ac5d625968083cbd718e1af7eac54197ed3d404dfff9467c3a8c88/pyobjc_core-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2581e8e68885bcb0e11ec619e81ef28e08ee3fac4de20d8cc83bc5af5bcf4a90", size = 827410 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-accessibility" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/24/20/18a45998ae8bf9ce532a29f8eaebdaa7f15a7f77b3c34a8304714b393166/pyobjc_framework_accessibility-10.3.1.tar.gz", hash = "sha256:c973306417441e6bed5f9be6154e6399aa7f38fa9b6bcf3368fa42d92ef3030b", size = 29349 } wheels = [ @@ -2103,26 +2211,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ec/5d/0ffe3abc230e694e0a8aaf8f9a8c4f4f3b7f98787d53be5a5eba979654ad/pyobjc_framework_Accessibility-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:94dbc5f223e6485820c14e7dee99d8f4d5cbf0600353033822dcab7ec4bc998e", size = 10653 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-accounts" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cf/be/a4e4eeebfa140f0e00fe2fb882802cc4a5fa7f12c7fea01e35314fcf276c/pyobjc_framework_accounts-10.3.1.tar.gz", hash = "sha256:3d55738e7b3290af8cd4993fd2b670242a952deb995a69911be2a1be4c509a86", size = 16180 } wheels = [ { url = "https://files.pythonhosted.org/packages/27/8c/23a9128a0252d6ef7643edd5c90d18699fb7a8ae9849e47806408d3d15d2/pyobjc_framework_Accounts-10.3.1-py2.py3-none-any.whl", hash = "sha256:451488f91263afd23233287f223ba00c0ee5c93d64cd10e133d72bc6a0fc48aa", size = 4727 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-addressbook" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/21/0a/68769f71cbf9f46070059def94a5c7b0b218626652d7aa589e15f4e8b876/pyobjc_framework_addressbook-10.3.1.tar.gz", hash = "sha256:cde99b855c39b56ca52479b0a1e2daa3ef5de12cebfe780c3c802a5f59a484cc", size = 84696 } wheels = [ @@ -2132,67 +2240,67 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c0/b2/730fe2665b385fe5ad59fee25d562ed182f3369885d467aafcb369fb9c63/pyobjc_framework_AddressBook-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:f25864847b4a81289dd08e7052455699ee011a4df98f4da0b07f46523c212592", size = 13610 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-adservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ab/9b/eaeb7c8f30899979113b91d8317efd30743d335bdaaa8fb88434e7bf7616/pyobjc_framework_adservices-10.3.1.tar.gz", hash = "sha256:28123eb111d023f708e1d86f5f3f76bd4f6bb0d932466863f84b3e322b11537a", size = 11838 } wheels = [ { url = "https://files.pythonhosted.org/packages/c7/85/bfd64830a47b363ae31e2366ec68da065c35abd9fc08adaa4cd6daa48d42/pyobjc_framework_AdServices-10.3.1-py2.py3-none-any.whl", hash = "sha256:c839c4267ad8443393e4d138396026764ee43776164da8a8ed9ac248b7d9c0d9", size = 3105 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-adsupport" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/87/cf/9b40ef87f1315858e3dce9f807b359e43a6183616a6a8d2caab533d49a3e/pyobjc_framework_adsupport-10.3.1.tar.gz", hash = "sha256:ba85a00cf20c42501d8083092f7ca0fcd1e616b1725e6512e75bcb60a6d58528", size = 11991 } wheels = [ { url = "https://files.pythonhosted.org/packages/20/3e/3d43c0a398390c358a777fec7ccf9cf94523cc41618a59fcf72dc2172990/pyobjc_framework_AdSupport-10.3.1-py2.py3-none-any.whl", hash = "sha256:0e403ec206ada472b2c0b129ed656342a97c20110ca8398ab907100516b0e48c", size = 3018 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-applescriptkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5c/c4/42e37476f31dddecb3d7b83b076d5e94b754837e2326b0218227b20f96ec/pyobjc_framework_applescriptkit-10.3.1.tar.gz", hash = "sha256:add2e63598b699666bcf00ac59f6f1046266df1665bec71b142cd21b89037064", size = 11779 } wheels = [ { url = "https://files.pythonhosted.org/packages/0c/0b/6638a036e5e4b8451d9c5e96da5ec1bfcf4bee68b09b2e28158445d767e4/pyobjc_framework_AppleScriptKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:97ce878ff334b6853405a62e164debb9e6695110e64db5ed596008c0fde84970", size = 3930 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-applescriptobjc" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/80/9e/db9d93764db336ed53da548cd7b52b6fbd7d493101b801b164f5c1f5fce8/pyobjc_framework_applescriptobjc-10.3.1.tar.gz", hash = "sha256:a87101d86b08e06e2c0e51630ac76d4c70f01cf1ed7af281f3138e63146e279b", size = 11797 } wheels = [ { url = "https://files.pythonhosted.org/packages/94/1f/700ba04ece5f7c654cd58617a26427a0337e21003f1efd38132af48e0427/pyobjc_framework_AppleScriptObjC-10.3.1-py2.py3-none-any.whl", hash = "sha256:2d64c74a4af48656bb407eb177fe5f1d3c0f7bd9c578e5583dffde8e3d55f5df", size = 4027 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-applicationservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coretext", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coretext" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/66/a6/3704b63c6e844739e3b7e324d1268fb6f7cb485550267719660779266c60/pyobjc_framework_applicationservices-10.3.1.tar.gz", hash = "sha256:f27cb64aa4d129ce671fd42638c985eb2a56d544214a95fe3214a007eacc4790", size = 182738 } wheels = [ @@ -2201,26 +2309,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a5/44/44821633fb0a94e5072997eb56496a72c071ed22a1c93e53915b5a14dbb5/pyobjc_framework_ApplicationServices-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:57737f41731661e4a3b78793ec9173f61242a32fa560c3e4e58484465d049c32", size = 30950 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-apptrackingtransparency" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/75/63/b7039473d92211938645c44069b2e8bc65eefc229a3aac1ff8ccf0f13415/pyobjc_framework_apptrackingtransparency-10.3.1.tar.gz", hash = "sha256:2e381db5f7d3985207b5ff2975e41bf0f9147080345b2e1b4b242f8799290d04", size = 12547 } wheels = [ { url = "https://files.pythonhosted.org/packages/f2/ab/7be81bd560ea539f5fa39c81c55af759d69a667ad9bb81efb2094e8a7b1c/pyobjc_framework_AppTrackingTransparency-10.3.1-py2.py3-none-any.whl", hash = "sha256:7c0e3a5cad402e8c3c5da1f070be0f49bb827e6d9e5165744f64e082633a4b45", size = 3459 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-audiovideobridging" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f9/f8/437666f24f295986ad9ea77a694f7db98889a8367fad46d93b84ae028e28/pyobjc_framework_audiovideobridging-10.3.1.tar.gz", hash = "sha256:b2c1d5977a92915f6af2203e3b4c9b8a8392bc51e0fc13ccb393589419387119", size = 59209 } wheels = [ @@ -2229,13 +2337,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a7/3f/cd2f1187295ba9824129823911bdbd984bb49d9c86336c08d77a8f19bccb/pyobjc_framework_AudioVideoBridging-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:b1fb0af1df78800205cd7a7cd90e58b640513bbb944fe6a8d89df43e626a27a8", size = 11094 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-authenticationservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/35/3b/12082a13266fed356222a5c6c3eaf6ddcf21099f7a5b76b3fff58568042a/pyobjc_framework_authenticationservices-10.3.1.tar.gz", hash = "sha256:0ac834f4a5cbe3cf20acd4f6a96df77bc643a1ae248e394d06964db9fe0d6310", size = 86405 } wheels = [ @@ -2245,13 +2353,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/27/d1/0d3a08a92ca7dd92311f8b13e08f41f2f5d558bad17a4db53dcd007b951a/pyobjc_framework_AuthenticationServices-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d715bbdf1c94ea838830930a41de0554905760943cff1510268d8e485c826ee8", size = 19988 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-automaticassessmentconfiguration" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/67/0d/19f8aee86e91da5a9f6954870f21d839b835a20e84eb2221b839797be705/pyobjc_framework_automaticassessmentconfiguration-10.3.1.tar.gz", hash = "sha256:f7846d04493e90eddbacfb7cffebc11b3f76f0800d3dc2bec39441732a20ac56", size = 22477 } wheels = [ @@ -2261,13 +2369,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3b/1c/c761dcab6f5ea6f1137a4bc9e1ce584010daaabbcdf4c11d66a0e490b2b1/pyobjc_framework_AutomaticAssessmentConfiguration-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:578512ae1443e031c3fbfec7eefa71e5ac5fc8cac892ad7183c5ac0b894d494d", size = 8915 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-automator" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/88/ca/fe39648043bf7ab2e5f09707cca9254277555c1a09973ade71fc029f7dff/pyobjc_framework_automator-10.3.1.tar.gz", hash = "sha256:330042475479f054ac98abd568b523fc0165c39eeefffc23bd65d35780939316", size = 195097 } wheels = [ @@ -2277,16 +2385,16 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/00/0c/4c81e55eb886112756177f86389558ee0b04ec060b4eaca122e4f83f8bdc/pyobjc_framework_Automator-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:2f482464b3f91405a5a59e3b96ae89c5062af81023ea0fc803353fdfe8cc4a9d", size = 10372 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-avfoundation" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreaudio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coremedia", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5b/4f/0f509c925c28d4b0ea709ccb9fd9a229c6552187f7506aa1e583d66cf658/pyobjc_framework_avfoundation-10.3.1.tar.gz", hash = "sha256:2f94bee3a4217b46d9416cad066e4f357bf0f344079c328736114451ae19ae94", size = 695146 } wheels = [ @@ -2296,14 +2404,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/db/bb/b7eb1bb9ba12a0717c944f7a60f6decafa745cf7281a935671ccd0739b42/pyobjc_framework_AVFoundation-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:00889eb915479aa9ea392cdd241e4b635ae0fa3114f043d08cf3e1d1b5a23bd4", size = 67995 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-avkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b5/de/7de605cea8176d69a41503dd544c0af02760c4518be3049b877563cc0c36/pyobjc_framework_avkit-10.3.1.tar.gz", hash = "sha256:97ca35b5f0cec98f5c8521fedb8537bb23d82739b7102e4ac732d3c3944c8ccc", size = 38986 } wheels = [ @@ -2313,13 +2421,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/25/ae/158378a4753102daeb89e5c0f5ae827c97015ab8d84d4d021965071d386c/pyobjc_framework_AVKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:91bf61fa8d8ef3764345b085038a4081165a8c54b4f0c2a11ee07f86a1556689", size = 12282 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-avrouting" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/66/d5/b3012c90b18722b9d8e27f6a570ac534da89e4902bf5805f0bb39e340891/pyobjc_framework_avrouting-10.3.1.tar.gz", hash = "sha256:7026059b24daf8e1da05d7867f450e82abe412fe5c438faf9344f46e3b83da39", size = 18663 } wheels = [ @@ -2329,13 +2437,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/aa/58/60bbff72a9aec1b8419461e94946a531878385993aaca1789795906fe69e/pyobjc_framework_AVRouting-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:186e891c2a271492612b3db2b5c2050c56ed1bfce1f6146de8dbf05e7cd7623b", size = 8628 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-backgroundassets" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/bb/be/6a0039ac75e7d9b84f7250d2301e0fe6529c0db6c137e398e31d04f65629/pyobjc_framework_backgroundassets-10.3.1.tar.gz", hash = "sha256:5e1198f81db6f30ead2a55e8ea39264f9fce83dcf8e31a68e5f0ea08c5cfe9b5", size = 21762 } wheels = [ @@ -2345,16 +2453,16 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/11/da/f25864ee44ccc600a7b93c07e0a7b45f88a9ed302de708c88bd9edfd9ba5/pyobjc_framework_BackgroundAssets-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:aed2307c7fdd690e4dd214cbfacf4e7d5dd07e6cdd88ce1c02c4ddde3deea843", size = 10224 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-browserenginekit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreaudio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coremedia", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/48/09/61f1688824a500f74e4fee94cec3ec3bef87e58a5205026761e4d292f027/pyobjc_framework_browserenginekit-10.3.1.tar.gz", hash = "sha256:0f6ea100bcf06f2b3f915dab27cf2f038698b39510fb47d3769f72ff62c1e80b", size = 21016 } wheels = [ @@ -2364,52 +2472,52 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/4c/8c/4b11a2cfd7df34507c8da6c4c54da4de135e856f9bca2d86524c8e67b4c1/pyobjc_framework_BrowserEngineKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d5aeff43abed7e87f637086a05f1b77083cfc7cab07c09c447ae2b23621b2945", size = 10480 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-businesschat" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a5/19/7414a07489dbeef3b1bd40845cb9bd0e035062da3879ca20fb01a7901302/pyobjc_framework_businesschat-10.3.1.tar.gz", hash = "sha256:53e52981f9da336fcaf6783e82509e06faf8868931213ac70e6bd7395a5859a4", size = 12088 } wheels = [ { url = "https://files.pythonhosted.org/packages/85/0e/b3f16873394b9d88c3217a5fe3e736e36af049f813c18af5a1bf38279cd8/pyobjc_framework_BusinessChat-10.3.1-py2.py3-none-any.whl", hash = "sha256:952b60f558e3d3498e6191d717bf62c1803f4e1ad040ae29d130090671ec004f", size = 3088 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-calendarstore" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/10/85/c4bb713e7e4d3f197ac975f5425ecf5469c1ea91d7b80d32eb4437b004f4/pyobjc_framework_calendarstore-10.3.1.tar.gz", hash = "sha256:21f627b0afb9a667794b451dd3a03f12ea3f74358dc5977c33b8ecc8b9736c27", size = 62920 } wheels = [ { url = "https://files.pythonhosted.org/packages/e3/7f/2e3325244afa35fa610757a7f0488965b6fe89504d13ad2325527f515139/pyobjc_framework_CalendarStore-10.3.1-py2.py3-none-any.whl", hash = "sha256:7afb59e793ea6d28706423faa50bb1f25532d8ed7388c8540596ce41891445ca", size = 4865 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-callkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d3/b2/be5cf42e2b288073fa5d693d869ac2fbfb091a34e8edd5aa67f50fa6982f/pyobjc_framework_callkit-10.3.1.tar.gz", hash = "sha256:350390023e9ac98ff6c91b1f51da2489eef2e23aa649d0f63c13cf1d8be1e0df", size = 31907 } wheels = [ { url = "https://files.pythonhosted.org/packages/92/01/4e419642221949f459459633be2e0ef456c7cdb8fb02644a805b31008e86/pyobjc_framework_CallKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:495354bea298efdc81c970154083b83aff985f2c294d4883a62de3cc4129e34e", size = 4916 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-cfnetwork" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/fb/e6/e1d6b0d0b21ba5241712389aea46dba4ee9d5c955738076f5ec9d75b5f29/pyobjc_framework_cfnetwork-10.3.1.tar.gz", hash = "sha256:0e4c51a75dbf4e2b1c0d4ee60a363f9d31d682d2dd2f6b74aded769d2d883aa8", size = 66882 } wheels = [ @@ -2419,29 +2527,29 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e7/2d/bc2e628e12d0bd7e287ed8f7af3b0df347d1814d950a566fe3cd48e01480/pyobjc_framework_CFNetwork-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:f6a5d6fe5e230cc0d53b9673902f1571ab68b542f3630d7c1319ea1e3e480f22", size = 19002 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-cinematic" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-avfoundation", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coremedia", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-metal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2a/83/90a5f31fd89bfa030c812c869ab69cf0e333e13ee2e3c1e4877ed883d6d3/pyobjc_framework_cinematic-10.3.1.tar.gz", hash = "sha256:7edaaa7e325aeb39cd0c33329c25783dd54af294229884556daad36d1d1b9d72", size = 19342 } wheels = [ { url = "https://files.pythonhosted.org/packages/8f/d1/cc9c887e748d172fc0928f0d80cf03f598daba9757ea08187e6295d6dc4c/pyobjc_framework_Cinematic-10.3.1-py2.py3-none-any.whl", hash = "sha256:48bf35d594f4f010266a028bbf93bd953cc78db7658d3c614e219b482c8d73b2", size = 4193 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-classkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a9/b8/cc33b734656f6617394b410a9805d05511aecdb665591936acfd66060dfd/pyobjc_framework_classkit-10.3.1.tar.gz", hash = "sha256:e15700d32007bf77c5c740bc9931c864bb7739cdfcd2b0595377c3ed35ecfe25", size = 32503 } wheels = [ @@ -2451,28 +2559,28 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/68/26/1a566a950018abc0b38ecef709810ad87d1e33126624e3b751be3370881d/pyobjc_framework_ClassKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:776a600182b7de58676ac661b235356f46683e758d99db1cf60f52aac335389f", size = 8673 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-cloudkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-accounts", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coredata", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-corelocation", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-accounts" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coredata" }, + { name = "pyobjc-framework-corelocation" }, ] sdist = { url = "https://files.pythonhosted.org/packages/84/2d/22c51450dddeb9d851529f90ebd4f15fc12a4f3c9b2ceae4df8841fde64e/pyobjc_framework_cloudkit-10.3.1.tar.gz", hash = "sha256:4c7db72c2bb2fcf63365df91bf2eefa83cee4004606b901e1da89b75da652309", size = 98916 } wheels = [ { url = "https://files.pythonhosted.org/packages/a1/68/49c0dac7cf069a13352e9bb7092aa0a0caeb5646e2c3a7b9eabfb07279ce/pyobjc_framework_CloudKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:53670f47320063b80aa60edd2d813308dce85dfd2112461dd13c060aa9e5b47a", size = 10475 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-cocoa" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a7/6c/b62e31e6e00f24e70b62f680e35a0d663ba14ff7601ae591b5d20e251161/pyobjc_framework_cocoa-10.3.1.tar.gz", hash = "sha256:1cf20714daaa986b488fb62d69713049f635c9d41a60c8da97d835710445281a", size = 4941542 } wheels = [ @@ -2481,39 +2589,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/93/1f/b203c35ac17ff50b101433783988b527c1b7d7386c175c9aec1c89da5426/pyobjc_framework_Cocoa-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:de5e62e5ccf2871a94acf3bf79646b20ea893cc9db78afa8d1fe1b0d0f7cbdb0", size = 395004 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-collaboration" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0d/cd/8bc8e3c4cf93b1044d5e582904ec5c55656f4385bd25f86f924b4ed25ae3/pyobjc_framework_collaboration-10.3.1.tar.gz", hash = "sha256:bbca3de3679b058cbb89ad911e3bdfe491a02b4fa219d5f9219c022774ba237a", size = 15830 } wheels = [ { url = "https://files.pythonhosted.org/packages/a0/c0/b26f50c0669f49fa652a96b6496deba5c9181ddec5ac59c4de8251666857/pyobjc_framework_Collaboration-10.3.1-py2.py3-none-any.whl", hash = "sha256:889b1e00bdea09c2423e9b8d493492ec45a70787ddc533bf67d060c7ec0e1f78", size = 4490 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-colorsync" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/43/16/b5cf65d3cdae2127a868e06b21e9c59e2ef531e65c4ee58afcaef2c4fe69/pyobjc_framework_colorsync-10.3.1.tar.gz", hash = "sha256:180960ed6f76084b35073eff49fcca41a8fa883c3236949a40f75daa28ee8f94", size = 31940 } wheels = [ { url = "https://files.pythonhosted.org/packages/2c/3e/273fcd5803daf481ecc3d76adafd455040375acd63582e501cb3e2717de3/pyobjc_framework_ColorSync-10.3.1-py2.py3-none-any.whl", hash = "sha256:0c37075e9b0f1dabc0aa1755687e1a5dada08ae0914ebb593c7810bf8090cf83", size = 5599 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-contacts" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/eb/a9/112ee53259220322f6729c446fd7b779d3bae7b24804bd342f51764dc6bc/pyobjc_framework_contacts-10.3.1.tar.gz", hash = "sha256:7120b5593a20e936cb5589b93ef7fd5558c86bd6ec8003f427afb87c04bbea20", size = 68431 } wheels = [ @@ -2523,14 +2631,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b3/8a/37fbb2012ca0a15aafdf1aff03317c11ed60d14ebcd1418638897075d5e6/pyobjc_framework_Contacts-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d47f694977cf33f5d0b73e2f111edcd57f2ef0cd9a6a38e03b1dea965b8657cc", size = 12681 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-contactsui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-contacts", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-contacts" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ad/17/ce9b512e29ca92eb519328d0fc1e12b6b048ac379447c7f4f2be4266599e/pyobjc_framework_contactsui-10.3.1.tar.gz", hash = "sha256:51601501d5bc94c59ad458c7bb1d1994c497b373307dad8bd2ea2aa348f66c4a", size = 17921 } wheels = [ @@ -2540,13 +2648,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/4d/56/63b61f49146a9d1890b8a06f93bf99fd15d61afdc65f6d75689aec53217c/pyobjc_framework_ContactsUI-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:62ae604a000233c729712e420de734c97afdd9187fdd0bef8e61fbc8c4f6eda0", size = 8251 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coreaudio" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c5/fe/39351e6a58f4a9b1fce5a5e982830612277233084fe72b1d84b4de890f3b/pyobjc_framework_coreaudio-10.3.1.tar.gz", hash = "sha256:c81c709bf955aea474a4de380b187f3c2e56c864ca7de520b08362b73070c795", size = 125676 } wheels = [ @@ -2555,14 +2663,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/31/50/3917e5190b65e4f29a5977c9713651c779f48753042d2fdc3f8dbda12353/pyobjc_framework_CoreAudio-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:21cecd1b023b6960d1071c106345656de45a399196701b07c7e5c076321f25ad", size = 36199 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coreaudiokit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreaudio", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1f/4e/79a20d1ab459467de5695f96057e034d6457b061da68951b41af211b1fe3/pyobjc_framework_coreaudiokit-10.3.1.tar.gz", hash = "sha256:81f35d5dc45cda043e01f0ca045311f4aebc36c51cb71e859b30ea0edf90b3db", size = 19761 } wheels = [ @@ -2572,13 +2680,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/43/df/910252ab44c47e48421f57be17c539e2f828653834cfbc7343e9f379db4e/pyobjc_framework_CoreAudioKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d5b3adabd7278e64a0deab6d0f6912bfcc667bc26054f5141a556897157dd8f9", size = 7452 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-corebluetooth" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f7/69/89afd7747f42d2eb1e8f4b7f2ba2739d98ccf36f6b5c72474802962494de/pyobjc_framework_corebluetooth-10.3.1.tar.gz", hash = "sha256:dc5d326ab5541b8b68e7e920aa8363851e779cb8c33842f6cfeef4674cc62f94", size = 50210 } wheels = [ @@ -2588,13 +2696,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f0/a4/ed61aba4cd2d66d0569669d047bcaf249fe28dd79331015fd0d6387dbd60/pyobjc_framework_CoreBluetooth-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b8becd4e406be289a2d423611d3ad40730532a1f6728effb2200e68c9c04c3e8", size = 13942 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coredata" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cc/17/1929fabc88d265373ce2b5e5c3136aae03c30ee42df66bd0810fa71328da/pyobjc_framework_coredata-10.3.1.tar.gz", hash = "sha256:8a75094942c8f3ddc1bcbde920c87658d7bb4c7534a4652e60db42d17f4b4a4a", size = 229850 } wheels = [ @@ -2604,26 +2712,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/36/31/a18ce8a793a4129968409199153799aac71b2461b994a7fb8125e0fa723d/pyobjc_framework_CoreData-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:2f1f4e1217fc02f66435dc2a5cb2e0b41c684c435f13d96bf05cd3d1e0ad4e2c", size = 17130 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-corehaptics" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6b/04/ef530d0c30cf81a772ddee64cbfeb7cafd9428d87df96bbc6eb41b77d80f/pyobjc_framework_corehaptics-10.3.1.tar.gz", hash = "sha256:5a7cc117c0b64428e1f08dc9c8b76dbc5d8f61f80dc41e911d11ddee4e0e2059", size = 36854 } wheels = [ { url = "https://files.pythonhosted.org/packages/2b/70/b41b0423b1dce4c98e87787c5af254275ad88db1a781eca5d8d440a4c882/pyobjc_framework_CoreHaptics-10.3.1-py2.py3-none-any.whl", hash = "sha256:163b83ea727cbac5c0963d16ffda89c9f1626ed633d5e52830c7918b8599a693", size = 4987 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-corelocation" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/06/35/8cf7ab8f9b7be5b81deac4d74fdc89607a3eeb901f785cc7d50332eaa275/pyobjc_framework_corelocation-10.3.1.tar.gz", hash = "sha256:8ae54e5bd4c07f7224639d815f7a6537fadee17c11cb35dd99c2804bac1825ab", size = 89219 } wheels = [ @@ -2633,13 +2741,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c4/85/aec923825469aa315d1fbdf5cd5988158fee5f0740f44b0c18b0b6624fd6/pyobjc_framework_CoreLocation-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:5c4ded6388f99a18ce2b9d7082b8a43a19b6d9f8f121e2147d10bb37a25e1714", size = 12840 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coremedia" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/68/9f/5e500c16472053db65dc917b7ea9cdc0fa8fde140ea4c38500a4c341b0a4/pyobjc_framework_coremedia-10.3.1.tar.gz", hash = "sha256:bc3e0cddf5f546b5d8407d8f46b203f1bd4396ad5dbfdc0d064a560b3fe31221", size = 180773 } wheels = [ @@ -2648,13 +2756,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/cc/47/2af2541dcd14c7d2891a10b31d6b285099963be2a67d3778ce92458592fd/pyobjc_framework_CoreMedia-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:98b8ab02e6ec979007b706e05166e16bd61121e47fbc6e449f4b2de2c58f3cb6", size = 28679 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coremediaio" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/08/67/1c22ff55baf5018d3ca4979f8c319e055ecff8b51ea91d53b8654503cc35/pyobjc_framework_coremediaio-10.3.1.tar.gz", hash = "sha256:5da3ed78475223dd3400fdb55fb97d543a248086f5cf8b77bf4aceac3df1513c", size = 88655 } wheels = [ @@ -2664,13 +2772,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d8/2a/cad9e2d9a234c805cf11d5f5b62cb7ad5e30ae0ba5814ddfced8ec3527b4/pyobjc_framework_CoreMediaIO-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b3e9a9813bf5331bd0981e0a66ff380c5c927854f644e5cb62a2beaabd73b15f", size = 17146 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coremidi" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/bf/9f/38d8668499e0c590e51b3f3091d972e09a1f45e4efba94373c22d23d2b88/pyobjc_framework_coremidi-10.3.1.tar.gz", hash = "sha256:818454b56edae082a3a4b4366a7e93b8bb54856be01ee21bb8527a22a4732efc", size = 78441 } wheels = [ @@ -2680,13 +2788,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/5d/d1/fc3226b125b0c7359539c508e939ad28f67acd487c628b3828c80a65720b/pyobjc_framework_CoreMIDI-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:bbe2bfb537e8adcca703a2c76b21ca1741d32691205af00a5ec67c025ee5d8e1", size = 17920 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coreml" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5b/a2/08a73df17f344700f48444e3000ebdf0ca78765bf0816387de7392380255/pyobjc_framework_coreml-10.3.1.tar.gz", hash = "sha256:6b7091142cfaafee76f1a804329e7a4e3aeca921eea8644e9ceba4cc2751f705", size = 66750 } wheels = [ @@ -2696,13 +2804,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d8/2e/75833ebb0b3037c32836d8a713bf8113cfb9420ee1c882e60177b5e892eb/pyobjc_framework_CoreML-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:4bd3f1acfb3245727727b71cbcf7d21a33d7e00fa488e41ad01527764b969b92", size = 11585 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coremotion" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6c/77/cef3cee6010e926754cc80faa455b5a7530d740f9b5a83a94fd4bd34484a/pyobjc_framework_coremotion-10.3.1.tar.gz", hash = "sha256:6ba61ffd360473b018702b9ae025eb16b8aaa45c6e533121522f26eef93a9f71", size = 54459 } wheels = [ @@ -2711,14 +2819,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fb/b3/521793543cc0266d6a6a2e4be3b660d99d0e16508cfa54436c116597b49e/pyobjc_framework_CoreMotion-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:9b78d2bcc71149821a49266eb548faea23abd7a25b7cd3f7a7f20b1d343a8786", size = 9794 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coreservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-fsevents", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-fsevents" }, ] sdist = { url = "https://files.pythonhosted.org/packages/18/c6/9214c4e64a22e92233f67f6518dc60269b30b317a169861f8cb8150adaef/pyobjc_framework_coreservices-10.3.1.tar.gz", hash = "sha256:2e46d008ee4ff586420175888c45f8eb0f002ed5b840c8f7893c560af01b2d72", size = 859909 } wheels = [ @@ -2728,13 +2836,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/82/41/a14f936b823d615bf799341adebed81b26bd641a0962e313f008bf23e0d6/pyobjc_framework_CoreServices-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:ccb64113ee612a05308ab8ed57ec224e22445d5a125bec11e24c35d58d1f77e4", size = 29751 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-corespotlight" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9f/fa/e0ef8d255265a2aaa575244df3d629c46a4eda6c64a210a9faf62fd70772/pyobjc_framework_corespotlight-10.3.1.tar.gz", hash = "sha256:6b8ad243a65943d631434a9ff4696458cdd3d0cb631cfeb501a967fe29445c30", size = 69476 } wheels = [ @@ -2744,14 +2852,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/cb/64/43e4d5505e16f5570e777e19ea9b6045cba45de8c9d2849aa003462a69c7/pyobjc_framework_CoreSpotlight-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:ba5a20e860af7246da67bb00db15d8bd5c5110b8a12a44568bd68030f51db478", size = 10091 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-coretext" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9e/9f/d363cb1548808f538d7ae267a9fcb999dfb5693056fdaa5bc93de089cfef/pyobjc_framework_coretext-10.3.1.tar.gz", hash = "sha256:b8fa2d5078ed774431ae64ba886156e319aec0b8c6cc23dabfd86778265b416f", size = 233428 } wheels = [ @@ -2760,13 +2868,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/6d/7a/850261594a2a7ec54f27449db2c2494cc0b79897c765fea1581e03268f7e/pyobjc_framework_CoreText-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:51ca95df1db9401366f11a7467f64be57f9a0630d31c357237d4062df0216938", size = 30331 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-corewlan" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9f/b0/6e708d931e85db91de439c080d3af77422d7935b7527ce81888f8ff6ed8b/pyobjc_framework_corewlan-10.3.1.tar.gz", hash = "sha256:d340d976b5d072b917c6d3de130cb4e7a944ee0fdf4e1335b2aa6b1d4d6b4e14", size = 57781 } wheels = [ @@ -2776,13 +2884,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/1f/5d/5740991885dc7bffff526148d6b8ea77dadba49ce6c1d42a6d14013006ef/pyobjc_framework_CoreWLAN-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:e7120d4f7a73cfc283ca499165e8aaf2628bfb82773917e144c293447cabbdba", size = 10283 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-cryptotokenkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/07/15/49981d93f8402c655cbda9181a55e0f5879715d3f6c344070ba41d2511f1/pyobjc_framework_cryptotokenkit-10.3.1.tar.gz", hash = "sha256:ef1c4a3b9bc5429eceda59724279428e1f8740df2c5a511d061b244113b6fd97", size = 48548 } wheels = [ @@ -2792,52 +2900,52 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/01/c9/eb29a4611eeb0b611671a392f7774d17cfa5ffd8c59440831cafd54d119c/pyobjc_framework_CryptoTokenKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b53fdc79a095d327dff7e68e2545b0825437520f105b1341e5f638e8e1afb490", size = 13241 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-datadetection" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/28/9b/8b3a633ef4a215095bf1e008f4921bb9647a61a1f5b24e8ab94e89473df9/pyobjc_framework_datadetection-10.3.1.tar.gz", hash = "sha256:5394350cd7e7f40562dc0777f26dd9ddf4a595d20cb6e3cd601938e9490c963e", size = 12682 } wheels = [ { url = "https://files.pythonhosted.org/packages/4e/1e/bc1dde224086ad91e2eedcebdb698f3d9a3c81b4b7da3b0548bd9c6a42ef/pyobjc_framework_DataDetection-10.3.1-py2.py3-none-any.whl", hash = "sha256:618ea90267fd4b83d09b557b67342ad5f3ac579090020e081dca6c664f1ae598", size = 3106 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-devicecheck" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/23/40/51f5e655f4d003227df3077151d20e8490e17e28043e0c4152cec9fcdfac/pyobjc_framework_devicecheck-10.3.1.tar.gz", hash = "sha256:7f6f95c84dc3d1f62aa07061f79b47d19463390d977e5afb444ef9fdd9177a9d", size = 13134 } wheels = [ { url = "https://files.pythonhosted.org/packages/2c/2b/9f22fc10b09daa6283ee5e9273aa6f25c61a1aee6afc44ce55fd353dfed0/pyobjc_framework_DeviceCheck-10.3.1-py2.py3-none-any.whl", hash = "sha256:9a3b291a2583bac2b65ff902c4b7872c1068736e249765906f530ae5a6eb8085", size = 3293 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-dictionaryservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a9/ee/ecf4fc40acfdc71a42f6efb7de6cd12b43ee73b3a2397872145584157aef/pyobjc_framework_dictionaryservices-10.3.1.tar.gz", hash = "sha256:c9fb8ed1b92f63c6f568bcdbadf628baab1cb8bb4cd01dbd65424d59c236a552", size = 10131 } wheels = [ { url = "https://files.pythonhosted.org/packages/57/2c/ded526049d60a7863bc08244454a4ae02250b15d2c07c16ad695bb4a71f6/pyobjc_framework_DictionaryServices-10.3.1-py2.py3-none-any.whl", hash = "sha256:e40933bc96764450dff16cd8ca8080ec83157a93ed43574441848ea52f24918d", size = 3505 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-discrecording" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e3/0a/07b7871e9bbfb59676be857046c8285549edaf285e8c1508b67db62ddf9c/pyobjc_framework_discrecording-10.3.1.tar.gz", hash = "sha256:47865c9a0d24366b6ede01d326d57404346c3d01e249f417bd2b0b3de00d6c54", size = 101624 } wheels = [ @@ -2847,92 +2955,92 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d4/09/65703b2911be89885d39129309af08c70f1b83832a23346afbae4f84e7e0/pyobjc_framework_DiscRecording-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:da84170af530cda7b1f32023d5e8b98b62914c573c6ef571e562473d0b94fe6f", size = 14979 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-discrecordingui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-discrecording", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-discrecording" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e6/5e/12669a09410b9707bd27ba93274cd9e817acc6d43ff358299974a52fa624/pyobjc_framework_discrecordingui-10.3.1.tar.gz", hash = "sha256:4b9c804a97c89001feddb58106cdc3e099e241314f7c4de062842d27b1318b68", size = 18181 } wheels = [ { url = "https://files.pythonhosted.org/packages/9a/78/57528e38d638bfb618f3d16b684b85a74c24e9443e3e986cc5dc1dc3ffda/pyobjc_framework_DiscRecordingUI-10.3.1-py2.py3-none-any.whl", hash = "sha256:cb25c70117a5c5eeb4ef74a96da48e2da171f01b7e92d1b7bbd7808068e8960c", size = 4344 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-diskarbitration" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4e/e8/9f1929c51bcfd78bde9763cc08200eb498528534664701730077beea31d3/pyobjc_framework_diskarbitration-10.3.1.tar.gz", hash = "sha256:0776318cb56f8e095066a880812c4fc5db2071687846e23a000a947a079f6c6c", size = 18667 } wheels = [ { url = "https://files.pythonhosted.org/packages/4e/e8/9670d42e001ad2577b7526fa1cb400328c4b3851e0b7171875fe43459a4f/pyobjc_framework_DiskArbitration-10.3.1-py2.py3-none-any.whl", hash = "sha256:f0f727435da388efd035bdd510607a5f5769b22be2361afc5b8d4ee081c70cce", size = 4432 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-dvdplayback" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/72/b6/7f7d140ce091b9813e11f1b980956e607b552ead399abed5a70662f721c0/pyobjc_framework_dvdplayback-10.3.1.tar.gz", hash = "sha256:1f7c22624dee9b1b54def15f12a3f7cacb28052cd864a845eb24b7f59de12257", size = 53047 } wheels = [ { url = "https://files.pythonhosted.org/packages/b6/32/62882a136a3f17eef51cf81e13d69159e448c51cc9b136cf2b32375426ce/pyobjc_framework_DVDPlayback-10.3.1-py2.py3-none-any.whl", hash = "sha256:c0fb2e96ce4eae8def642f1c4beaec2da3cdf61db1562d4b5199d1334d1a10fe", size = 7836 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-eventkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ac/c4/995108bba1fb40eac108501038ae44c57099310982d1a6339b6a5fa47d82/pyobjc_framework_eventkit-10.3.1.tar.gz", hash = "sha256:3eef14ba439be1c5bc47da561ccea3941daba663577efac7a58e3031d27e056b", size = 64043 } wheels = [ { url = "https://files.pythonhosted.org/packages/29/7f/1edbb57ab0cb591aa924279aabedf3fe508f62de136465adc44d77ab17a9/pyobjc_framework_EventKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:ad9f42431bd058ff72feba3bbce6fbd88b2a278c3b2c1cdb4625ea5f60f1ecda", size = 6413 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-exceptionhandling" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/00/88/1328bdac98aa75de421ffea4e16f0b894e39b4ea6569b3a109b531798d20/pyobjc_framework_exceptionhandling-10.3.1.tar.gz", hash = "sha256:ff6208777739f8a886d0cbfe20692b41cc4e5e0607419c47d2c5d405b6b4c6ee", size = 17129 } wheels = [ { url = "https://files.pythonhosted.org/packages/90/05/da9e1a8dce6d333d7b9e714c5c228b01b9208b827aaf2862e7c993541eb6/pyobjc_framework_ExceptionHandling-10.3.1-py2.py3-none-any.whl", hash = "sha256:79843a681a1d0f9ee2b7014dcf7e1182c99c83e49cf6cea81df934ebbdf4050b", size = 6670 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-executionpolicy" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/54/8e/e5a3c06123a4ec3b845dac82450f4f1b4e5b80c0863881fb538f900762b0/pyobjc_framework_executionpolicy-10.3.1.tar.gz", hash = "sha256:cc066dc8378fc2a1a4e6129c4d09e2076dc9a5b09925f8dd959aad591cbf9a44", size = 12825 } wheels = [ { url = "https://files.pythonhosted.org/packages/b3/45/559ddb59ce80f07c8c2ed81a3dd2b3ce7eb9399076cb556c8544dd444ead/pyobjc_framework_ExecutionPolicy-10.3.1-py2.py3-none-any.whl", hash = "sha256:f2eb203fa4c7dcf18a0ab3a4a94cb30a9f82cf888c237994dbbdb15adf01c8d2", size = 3343 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-extensionkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e7/6a/2803c373283c66eb0d38f139aa1bfa7eb9dc909bc470856ae2308f064e39/pyobjc_framework_extensionkit-10.3.1.tar.gz", hash = "sha256:91946030195fa17c5248655b10786ea60b9aee7d83a4627ba56768600b4e7674", size = 17592 } wheels = [ @@ -2942,13 +3050,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/83/1b/113201c23f9c9fc562b456362340669eb6744eb38081df093f6a9a7095dc/pyobjc_framework_ExtensionKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:c66797352b71a944810447c81133935656d8ea9bb847775a1532cf06d8deb1d3", size = 8286 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-externalaccessory" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/db/51/61ed6de7d4950f3810e0b5f95cad1a225a1fff8eef13223ebcbc659a4888/pyobjc_framework_externalaccessory-10.3.1.tar.gz", hash = "sha256:3ba1a7242448126b4af0fb93963790d0066766bcba2770d935111093e87b7b83", size = 20735 } wheels = [ @@ -2958,13 +3066,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/05/e2/d43cf99a6aed9de76c41bdc8f99ac39ba6926a39b01ae778bae844fabb3a/pyobjc_framework_ExternalAccessory-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:4771cddfed6422502831a9bf88fa572918d1ca71a3e34e068f442d1197630267", size = 9334 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-fileprovider" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2e/69/c4ebc6738e8a3f5e0c9394791434813fa2656dbe2356fdf4c611a57e7391/pyobjc_framework_fileprovider-10.3.1.tar.gz", hash = "sha256:63a4160e6cbede0f682145f4303ed889bd9f3c9fccfecdc32636a8d95aeceeab", size = 63649 } wheels = [ @@ -2973,39 +3081,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/89/bc/4465ba82721da0718c0555cdc74bb777ac40eaf5b49e97248530fca2fc62/pyobjc_framework_FileProvider-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:bb07a0b7e259030c7bc034c590c77a22e44427320c99bf74e5348551fe0da011", size = 18108 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-fileproviderui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-fileprovider", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-fileprovider" }, ] sdist = { url = "https://files.pythonhosted.org/packages/bf/5c/b130db2b86ff41da6422cd9ed54959202052c0b7401992b467c6cc29ec16/pyobjc_framework_fileproviderui-10.3.1.tar.gz", hash = "sha256:2a3f3b9b81aff216df76bc72c8e8730d7ba7f3b2412720f68b722bae58f82797", size = 12546 } wheels = [ { url = "https://files.pythonhosted.org/packages/ea/f2/1ddd3a5866a596daa4def91c3cb6e07f0a395232e49865f4e16c6929fb95/pyobjc_framework_FileProviderUI-10.3.1-py2.py3-none-any.whl", hash = "sha256:14be680a7fc78def5174ec5a6d890d407678cff723d6b359bba66bc0a78bd31a", size = 3317 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-findersync" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/67/70/0a2d490c88541912cab2d245093460190ddeed3bcde9faa3bc5e987c2247/pyobjc_framework_findersync-10.3.1.tar.gz", hash = "sha256:b4a08e0a87c54f62623038de1929fab018fe44fca5372a455bb524b9f90e9196", size = 14228 } wheels = [ { url = "https://files.pythonhosted.org/packages/ba/b5/bd7cd2bb1ac4c13da19309ce5db976f5b533ab8ec44744ec15963de7b131/pyobjc_framework_FinderSync-10.3.1-py2.py3-none-any.whl", hash = "sha256:d4778de8a9b386c16812d470d1ad44d7370970d1dbc75d8bea390d4f5cd12be4", size = 4478 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-fsevents" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a6/fe/53eb4883293b4920544570feb1d8290e937df706ee063a26061f3aebfa72/pyobjc_framework_fsevents-10.3.1.tar.gz", hash = "sha256:6269fd8aa3f62d8a6312e316043aca6d7d792812bff09b617bbd6ca9f0f6e440", size = 27274 } wheels = [ @@ -3015,13 +3123,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b9/32/7d7b848cb444737bc87d86f38a1eadf52907e4525506b3e72d4dd9ebb944/pyobjc_framework_FSEvents-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:282ebeeba0190524fe1d5d21d729ebcb7034e379a8039a6ccdf5f5c6e4470e02", size = 12989 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-gamecenter" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/46/2f/82cea539bd5a3c764c7acb065face9d1176011f58643323fde30f05997cd/pyobjc_framework_gamecenter-10.3.1.tar.gz", hash = "sha256:221ae88ee69816b95861b1a0dc781c1c17775d38fcf0388327620535479b6a07", size = 30111 } wheels = [ @@ -3031,13 +3139,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e1/39/b6c69bacd37b96143b7dd61be6bde201a7a5058ee085166cd42600927009/pyobjc_framework_GameCenter-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:6bd556e798cf52b94434c48cabf299060dd79b668f0021826995ceee520db8af", size = 19224 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-gamecontroller" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/49/6e/1ee46fe9870ce020529ce883c04291a7c7f43adad2b6fbc9b0c44d2549c0/pyobjc_framework_gamecontroller-10.3.1.tar.gz", hash = "sha256:f9f252b5fed5de2a8c7fdd2e302b6ed6e0b82015d7da75b28984c5ea5909345e", size = 94100 } wheels = [ @@ -3047,14 +3155,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ab/62/278908b0a50d654222ea699fcb95f9d8830627b6eee029fd0a0b576ccd6b/pyobjc_framework_GameController-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:e90afaa5a5d28771e60b4f60ff89b80037d4e9e558d680872810216299aea1a8", size = 20487 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-gamekit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/84/aa/897e74e41c80f0eaec994c4b0852e680e5eb22868d3a4681b46f06cf4032/pyobjc_framework_gamekit-10.3.1.tar.gz", hash = "sha256:7d21a8f45c32ac94ce0e70b6c6fe72928fe75cb1a6bd6d7715e2bf39b291b70b", size = 137591 } wheels = [ @@ -3064,14 +3172,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/53/e5/39cd4287f4d49114328c931fbf04b5870e7e6178eef4eec0d54a76813b7b/pyobjc_framework_GameKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:c861e575ed4543241adbc53162fb651395ba73c68a697f4b5aceaa61754e19c1", size = 22392 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-gameplaykit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-spritekit", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-spritekit" }, ] sdist = { url = "https://files.pythonhosted.org/packages/02/df/3a6e19a496dec873d26f255458a3e557f6e3aa004f04ca83f9de4e85e9e8/pyobjc_framework_gameplaykit-10.3.1.tar.gz", hash = "sha256:2035b81f7bc34b93636753cc3f9b06cd08171afc5c95bb2327a82fd3195f3c36", size = 55768 } wheels = [ @@ -3081,13 +3189,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/85/f2/78fc1e58328b9890355716b38c2cdfd11ec9d130f90a5be2ef68eb8d78b1/pyobjc_framework_GameplayKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:628406ca0d0ce283cc0735a4e532dd04a3a4d57a4c22c3ee4338ba64d1b13790", size = 13711 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-healthkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c0/68/fdda86963c5b3f86941623176acc2d7df03183ea9d3bbfff9088283d2bd2/pyobjc_framework_healthkit-10.3.1.tar.gz", hash = "sha256:45622fedb42bbd95dcc096248bbc41dacd857d9db120ff7310f74f3bad4b23e1", size = 113769 } wheels = [ @@ -3097,13 +3205,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a4/3b/4b52e663b5243eb62cb836300d5b6e2c425f4b027a0b31133d10093449d7/pyobjc_framework_HealthKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:5bfcaac3a3947d070611d1fed1abe8858e049ef0ab1050f46974a7333b6369f6", size = 19429 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-imagecapturecore" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2f/32/36b2b34e2ae902552854c1e5d24cb4d587875f4400791a30740213f57178/pyobjc_framework_imagecapturecore-10.3.1.tar.gz", hash = "sha256:9ce83c38b8ccee6b022faadb9cd7b8716119092cd41b6c2cabce3670101119bf", size = 81896 } wheels = [ @@ -3113,13 +3221,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/bf/b5/2d667e372f66db8af3a8dd9d3afcc2907f78bff44deeef7b38245348c374/pyobjc_framework_ImageCaptureCore-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d625d84094f51dd4389d1dea7c53480c3311dd19447d96b3c9eb06be5a935fd6", size = 16880 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-inputmethodkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3b/1b/28c9e10640e0b73dcd7b4693c9ee1fb5519443bd8fd5debb0066261a0abd/pyobjc_framework_inputmethodkit-10.3.1.tar.gz", hash = "sha256:637ba2da38da5f558443b4529b33bab276380336e977807347ee9dad81d42109", size = 24489 } wheels = [ @@ -3129,40 +3237,40 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/4b/eb/dfc9f160481226e2e46b4d94772aa2063ef87d4431f51fbd0766949951e1/pyobjc_framework_InputMethodKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:3fcd444b97cf2343a6c37b828dcc85080cc6a2c5ba508010dae4ebe836480d2b", size = 9786 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-installerplugins" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a2/cd/a9594b8200b1460630d21af18c9fc38741ff748c5457bf5958c5599795c7/pyobjc_framework_installerplugins-10.3.1.tar.gz", hash = "sha256:280808bbce36090b59197756fdb56c19838845a5fc25966a435dbc5fc4ddbbf0", size = 26514 } wheels = [ { url = "https://files.pythonhosted.org/packages/52/1a/06a5d257d20dcb64f9f20c4fb7cc518016add734a70c9547676af0d4131b/pyobjc_framework_InstallerPlugins-10.3.1-py2.py3-none-any.whl", hash = "sha256:2b32cde6fb8bbb3e1ffd04d7acbe3132291ad5937fc7af5820062e8aece7b5cc", size = 4392 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-instantmessage" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c7/fc/51a0707b48507ca4963333452fd17119cc325bbbefdac460bd960f6a935e/pyobjc_framework_instantmessage-10.3.1.tar.gz", hash = "sha256:bb1560a2f92a2def179b6381c17d406331b7818fa0fd1ba98f09ed94415f8a7b", size = 32767 } wheels = [ { url = "https://files.pythonhosted.org/packages/0d/04/089eee187804a418167d901c38cc4bb7cfb7045b53756fe3404011161a5a/pyobjc_framework_InstantMessage-10.3.1-py2.py3-none-any.whl", hash = "sha256:51a096e55a423423dbfbf19cc976a49915987ce68b9038f8ce3db9c3cde11718", size = 5016 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-intents" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/64/dc/120a1891de4ea2c4c5fa382100ac9706dda75a64dd6185367ddc8d89710e/pyobjc_framework_intents-10.3.1.tar.gz", hash = "sha256:89f0ed49c515b75c8811d9f6771ac635e799dfaf11921172729f8e0857c8c0e9", size = 361884 } wheels = [ @@ -3172,13 +3280,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/60/b2/a58d92da0d457754ead621108cca76c7157a9dba94449850389bac10a226/pyobjc_framework_Intents-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:6e77fea5fc4136888459c8ece7d48fe3eac3a37c665e9ba8aaeb18c1671eb083", size = 32464 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-intentsui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-intents", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-intents" }, ] sdist = { url = "https://files.pythonhosted.org/packages/df/51/3cff5de2db25fb516eba66480e90ceea293fc12d715d51a16ebb242c0893/pyobjc_framework_intentsui-10.3.1.tar.gz", hash = "sha256:68f42cabbd36889060d07b21f156f1dae78243d42b34c652448c687d07cbca62", size = 18822 } wheels = [ @@ -3187,13 +3295,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ce/23/d23acf3e451bc64d40d2b7cf0e03620399a3540c74b16e8d5b6a191cfbd2/pyobjc_framework_IntentsUI-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6c124ceb8e7b7a1f3fb6c2c159e47f9dca42ece6e1645d763235660ea98e7915", size = 9591 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-iobluetooth" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e9/98/b6aade04f7e07de0e81f0312c19bbd21ea61986ab8158a0986aec6c5efd5/pyobjc_framework_iobluetooth-10.3.1.tar.gz", hash = "sha256:bca424889d7fdd5bcb728d312e91ee681e73c0c2ac16ba37068603d699043d39", size = 226060 } wheels = [ @@ -3203,91 +3311,91 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/82/c9/4c7bf05da12c96657b51568be9177cf6a50b9ce0aa852d016f5d24fed68c/pyobjc_framework_IOBluetooth-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:17303009a3c1ac48eaaa2c3a96a114ef47adcb1fffbf965e7538447bb02adde1", size = 41421 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-iobluetoothui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-iobluetooth", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-iobluetooth" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d4/e2/3793269efe06505b1b4224ea395912c697896054bdc0bddcc3889796ceac/pyobjc_framework_iobluetoothui-10.3.1.tar.gz", hash = "sha256:6db82aeb360641b878f8ed73c2074db0425664d9411317b2e01962e0929fa29c", size = 19226 } wheels = [ { url = "https://files.pythonhosted.org/packages/d2/b4/47b9746727a7a199d674bb864525016bf2d22aae7e58021e96cbeb70c048/pyobjc_framework_IOBluetoothUI-10.3.1-py2.py3-none-any.whl", hash = "sha256:ae283c3fecbeb99adba9b3c3d5d06caaad741da726fc7a1dd50ecc0376e03ae8", size = 3653 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-iosurface" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b1/45/8cc7def9b73ec0c3423b7c4878ee3e02fd27e72085574f4c5b7b284bebc5/pyobjc_framework_iosurface-10.3.1.tar.gz", hash = "sha256:94e4a109a94f0e365bd60ce68aab6ff166fef6f30a40f7682c76902f5fc3aa34", size = 19262 } wheels = [ { url = "https://files.pythonhosted.org/packages/36/2d/c2519d5d8e78d60245d7336d2f44a48041b5ffee9b8f2bac9f5672033e6d/pyobjc_framework_IOSurface-10.3.1-py2.py3-none-any.whl", hash = "sha256:4171a33a09ee006ad28ba29e6d12cee821e2c0ba09b4beddae8db16580fb9bc7", size = 4572 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-ituneslibrary" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/53/a8/63766d37cc93e2a92a53bb3b5dc769fed0ac27509bfb251cb94878792432/pyobjc_framework_ituneslibrary-10.3.1.tar.gz", hash = "sha256:3899f8555ae02f6441a711892cdc6537404215b3d5f8a7ea4594f7460c58c9b2", size = 40017 } wheels = [ { url = "https://files.pythonhosted.org/packages/f0/c7/05cf8de68b85c574cf5929a4771cbdbd4ae2448d3381d4ef7f5066e510fe/pyobjc_framework_iTunesLibrary-10.3.1-py2.py3-none-any.whl", hash = "sha256:9485e986f6075d04e10c196e5dc36e4c3b60116a45849683a61c876e5fb45fde", size = 4821 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-kernelmanagement" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2a/b2/0c894451b949023e00b76e17e46ce65dfa30e5005c5500958d6f90a20fcd/pyobjc_framework_kernelmanagement-10.3.1.tar.gz", hash = "sha256:04c41bc0d0ce014318acf9e333aba302092d2698ec408cbf0b022f3a507ecfa1", size = 11933 } wheels = [ { url = "https://files.pythonhosted.org/packages/d6/75/140a6075df7c97c4e70014e696066d5b077d4116b9228287d87f63f1c1ca/pyobjc_framework_KernelManagement-10.3.1-py2.py3-none-any.whl", hash = "sha256:e07134bf3815370d3d9c37f9813edec12758f86fdbbbc67036ab72e8b767ddee", size = 3279 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-latentsemanticmapping" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6e/17/435b483033f21fa1d95132e93c0cedbf93567f00e6ffb579989e0c070f9c/pyobjc_framework_latentsemanticmapping-10.3.1.tar.gz", hash = "sha256:0bca94fd00f59f49874c8266bfacb09a7c56ad13b4d405c241421cef201f8943", size = 16630 } wheels = [ { url = "https://files.pythonhosted.org/packages/8c/ee/af2199401d4a6ce71b195338a2fa63bba0d33d9402622146906b741ec601/pyobjc_framework_LatentSemanticMapping-10.3.1-py2.py3-none-any.whl", hash = "sha256:c80c709b983273c8f29e86a04c52e98e8e6b0e723a400f7d6036fcabfd850367", size = 5035 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-launchservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] sdist = { url = "https://files.pythonhosted.org/packages/34/dd/53ff73cc0fbf1ad21d3acdd387830f793541dd023150866853e4f00d8dc1/pyobjc_framework_launchservices-10.3.1.tar.gz", hash = "sha256:7f16af2acabca0c2953eb7333bfe652bf853bb9d9e59b771f9d228468bccdea3", size = 20012 } wheels = [ { url = "https://files.pythonhosted.org/packages/56/77/848cc9be87327fed05e46a67ffa5abcc0edd5c0777c4b98b6e2e6537882c/pyobjc_framework_LaunchServices-10.3.1-py2.py3-none-any.whl", hash = "sha256:3ce840027b43c4bd95dc31aaa9b4bfff1d431e782669b4c95e2b12d386c05000", size = 3489 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-libdispatch" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b7/37/1a7d9e5a04ab42aa8186f3493478c055601503ac7f8d58b8501d23db8b21/pyobjc_framework_libdispatch-10.3.1.tar.gz", hash = "sha256:f5c3475498cb32f54d75e21952670e4a32c8517fb2db2e90869f634edc942446", size = 44771 } wheels = [ @@ -3296,13 +3404,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fa/36/c95b42c290d41687c2f01599feff82f4b6f9774006c4dd051f5d6a9949fe/pyobjc_framework_libdispatch-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a74e62314376dc2d34bc5d4a86cedaf5795786178ebccd0553c58e8fa73400a3", size = 15643 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-libxpc" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8e/9d/8a7eb8d3570f2f41fd265513655fbf28e2ab93155a0053f46277fd61b097/pyobjc_framework_libxpc-10.3.1.tar.gz", hash = "sha256:b3c9e9fd281b5610e3bef486e91570b0afa8ab8eb0c01c0baa5e2ec49ccb7329", size = 39868 } wheels = [ @@ -3311,70 +3419,70 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/8c/56/ef3ede2cea30acf4b251a5da5a2f32db17486acbf66ab8cfc28ae2a922d5/pyobjc_framework_libxpc-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:72a35a21f4bbbfb4a5c4c23e3180c3273b7720fe4cd150b975cb5d08cbc4fe13", size = 19531 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-linkpresentation" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b3/f2/8317cff954187875cc82dd8a08de69adbd1efb48451cd2b6836f347392db/pyobjc_framework_linkpresentation-10.3.1.tar.gz", hash = "sha256:535d452cc33d61074ba9bad7707d6c0a23d474fb045ed4322e5f87bfb0b7e865", size = 14174 } wheels = [ { url = "https://files.pythonhosted.org/packages/a4/6a/6347826cc12c01bfd2f6c804af1d99d4df8cd74440a412562b72cbbd97f5/pyobjc_framework_LinkPresentation-10.3.1-py2.py3-none-any.whl", hash = "sha256:e49ac094eb3a60a87f37edc24657feb051614a4d4464ad2580831288ead521f9", size = 3467 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-localauthentication" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-security", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d7/a9/bb2c2c3171a600dad5c7db509cdeef5a1a3cd7a22266a515145ebd5497b0/pyobjc_framework_localauthentication-10.3.1.tar.gz", hash = "sha256:ad85411f1899a2ba89349df6a92db99fcaa80a4232a4934a1a176c60698d46b1", size = 26240 } wheels = [ { url = "https://files.pythonhosted.org/packages/98/d5/3d5290b829f1f722b7593e01cc06406d6de404a35d91640241d885e2c01e/pyobjc_framework_LocalAuthentication-10.3.1-py2.py3-none-any.whl", hash = "sha256:565910d7d2075cd53c6d4ffdbb15d9b93267f1b1ba4c502d354778865d0dc2ec", size = 5678 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-localauthenticationembeddedui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-localauthentication", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-localauthentication" }, ] sdist = { url = "https://files.pythonhosted.org/packages/00/36/ba89365d6bdbed5db435e0b4e2dc310a977dab5a306453c4f7ef8de745f2/pyobjc_framework_localauthenticationembeddedui-10.3.1.tar.gz", hash = "sha256:f915190f6106b9f9234750abf48f87445c364ccbca8f8dd565bba1b66ddd55a3", size = 13305 } wheels = [ { url = "https://files.pythonhosted.org/packages/bd/e5/a393e16847f7605b80c643e961f60bed3c6c3b4758693907cdf88058a9bd/pyobjc_framework_LocalAuthenticationEmbeddedUI-10.3.1-py2.py3-none-any.whl", hash = "sha256:d69ef723f4525e6476e51bd166d56e97c9274500f98aa209a659e7567793dc01", size = 3559 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-mailkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d3/1a/683f99e9af1966de9173c1696946ec52b7d45d346aee8a638d1104eade95/pyobjc_framework_mailkit-10.3.1.tar.gz", hash = "sha256:90ad82786ae01a275aeec842e73b1fef12d9f91a67edcde8ff6a145859dc9f92", size = 26043 } wheels = [ { url = "https://files.pythonhosted.org/packages/21/99/b91c7329119c9ab2397307cb5e37f0e27a8a31fefbf8376cdc1b07b76ba6/pyobjc_framework_MailKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:7c403525e01bed0888946552e512ca4d1b018c3f6ef3d293fff85b90dc02a411", size = 4494 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-mapkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-corelocation", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-corelocation" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/53/f3/1f711e0311ddf3a838d1fe2ec1ab7c52cdb52d4a6144edcd2bd49becbe6c/pyobjc_framework_mapkit-10.3.1.tar.gz", hash = "sha256:f433228c404b9ef4a66e808995daccc1306f7123296317651078a6a734ac1ab0", size = 135465 } wheels = [ @@ -3384,53 +3492,53 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7c/bc/cb3ccf25e51650bce1a91f680aadf646cf238dbe92a38b73fb5fe17badbe/pyobjc_framework_MapKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:f14f90bcb68baee70a838b3cecb9d909da43175da49cbe90dd6cca57c37a6ae5", size = 22852 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-mediaaccessibility" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c1/d9/e82531ed727311b54bbbeb9da0bec5c098b8cf8017d541fc77175f4bf322/pyobjc_framework_mediaaccessibility-10.3.1.tar.gz", hash = "sha256:c249e1eee636e77b5f00db3bf85174cb3e0cb53ca991a17e53a1f200377f4289", size = 16607 } wheels = [ { url = "https://files.pythonhosted.org/packages/87/01/0adc256ed71a620be9fd357ac72b51a5b08af175104778201e0873de651f/pyobjc_framework_MediaAccessibility-10.3.1-py2.py3-none-any.whl", hash = "sha256:c4304ea53c7e85320b58d773cce2288f62dcb5b9c5a295be1ecfaa6645a9fea6", size = 4113 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-medialibrary" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/01/1c/c8355ad906e2051a3d73bef221ce559f417cd58e94dc5af1163bd3669c09/pyobjc_framework_medialibrary-10.3.1.tar.gz", hash = "sha256:703ffd0904fc86d4fbfbbd4952be43e91a6d477c53ce2868e4c18c3eb295f5c6", size = 17661 } wheels = [ { url = "https://files.pythonhosted.org/packages/d7/f8/d4afc0ccb1506ba85a873a238db934a83c349440f09c64d9ed287d5c5a88/pyobjc_framework_MediaLibrary-10.3.1-py2.py3-none-any.whl", hash = "sha256:25f16d610e3ea5d983175a6c07351596bd5dd2fcca194f1eac5686c670bbdb3b", size = 3974 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-mediaplayer" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-avfoundation", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, ] sdist = { url = "https://files.pythonhosted.org/packages/10/00/6d991d13624e8e9288ee289945737bd7e48cce6df7497ee25f2c39c4d173/pyobjc_framework_mediaplayer-10.3.1.tar.gz", hash = "sha256:97043df5ef89d4fbe217813e8f4ee1e226d8a43dee4eac00fff95e6b8a7772be", size = 77337 } wheels = [ { url = "https://files.pythonhosted.org/packages/b2/40/92912923eabb827ad6d97205d6091575118e312d58efd190766b38bb3b55/pyobjc_framework_MediaPlayer-10.3.1-py2.py3-none-any.whl", hash = "sha256:5b428cc28e57c1778bd431156c3adb948650f7503f266689559d0ece94b34e8a", size = 6548 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-mediatoolbox" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a6/8e/a4abb578ad0207ef723fac1255738ea2a3fab3c5b0b0c49a3bb30463257f/pyobjc_framework_mediatoolbox-10.3.1.tar.gz", hash = "sha256:f141056dce0dc16ec21be596fea58acb4a668045f53e12a0f250990d936b44f2", size = 21516 } wheels = [ @@ -3440,13 +3548,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/54/0d/ba00d64c83e4465f53f36af9e879749a1634b43c2ea0888a6bb7e0ce03a7/pyobjc_framework_MediaToolbox-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:4114fb3749dacf6dd83113823b846e77671c0e8b1209ca6e4402f09e6727c185", size = 13024 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-metal" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8c/5e/2df5fdb85a5753ebe6e1a1b1905da565a408a4f090f7c1d89f3a3143d18b/pyobjc_framework_metal-10.3.1.tar.gz", hash = "sha256:495307db0bfd2063f28b7c8fa350af71afcfbf5f5f2186a6a751b4cb2ef46a1a", size = 299751 } wheels = [ @@ -3456,13 +3564,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/43/e1/86702984f0f229be8ccc6c3f02f2d3598b67f17e898590ba127229fcbfda/pyobjc_framework_Metal-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:7fef3ebfd6cfbd7cbfe45aaa86dd32034303d933871d8450f4c990dbdefda176", size = 55756 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-metalfx" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-metal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5f/b0/a479ef7219d4176806e6f49718da59feb1dc222605f45f5e06777a6c6a3c/pyobjc_framework_metalfx-10.3.1.tar.gz", hash = "sha256:3ea0f259397523a84a320b3925dcaaa5c039494accc3cb412b63e6f7f66f9513", size = 21547 } wheels = [ @@ -3472,14 +3580,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2b/07/5597fc8d24cb3b01b7fdcb1986a41e5f2edd9aae9ba253b4d736768ccc73/pyobjc_framework_MetalFX-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b3ae624f7e0a5c60b856889753af560b7cbd1a5f47db01f120a668e429afd1c9", size = 10490 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-metalkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-metal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f0/6d/c5a782ee9def0feda16cf41c7326680f306293f4446185f3b0040e3e956c/pyobjc_framework_metalkit-10.3.1.tar.gz", hash = "sha256:905eaad9dce29082efd5cc56195337d2e8bff86ccfad36ec5127f818155ec038", size = 38269 } wheels = [ @@ -3489,13 +3597,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b2/b1/d38a5a62ab8a3db2728474370c3aa3e8fd21b889f2093eb4365c8f4bb4bc/pyobjc_framework_MetalKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:de632a7cdca1a0a13097a363dd441b9550ad91de6da6c88952c77acfd4b3a100", size = 9134 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-metalperformanceshaders" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-metal", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4a/f5/d6b25e063691ab304ed39b3d8121262f661b2e56630bf3b07476134e08a4/pyobjc_framework_metalperformanceshaders-10.3.1.tar.gz", hash = "sha256:1a9e91dc9e748834c95b7a596b943203761f6533352631c7abe612f804b23d50", size = 215419 } wheels = [ @@ -3505,26 +3613,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0c/ab/1b7e063d30e65629c653f4af89cf3072ede8a3f99cb1a690dd73d7bfc934/pyobjc_framework_MetalPerformanceShaders-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b02da6a5dc9088cadf38dce21aa39027bc668493876d3af684b91f039f123df2", size = 33121 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-metalperformanceshadersgraph" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-metalperformanceshaders", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metalperformanceshaders" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e6/0c/c00edcdc19f692d0d261d2a0c43f296f240c236704666e287e60dea23edd/pyobjc_framework_metalperformanceshadersgraph-10.3.1.tar.gz", hash = "sha256:4bf2045036f97dcaabbf16ee8527f1787c7e9366611b9b9ed4bfabc81c19343f", size = 81585 } wheels = [ { url = "https://files.pythonhosted.org/packages/19/71/0dbf9660d2a31470bb6e5d5338aed82c1906c4624e8629e24cf612fa4e14/pyobjc_framework_MetalPerformanceShadersGraph-10.3.1-py2.py3-none-any.whl", hash = "sha256:a0288c53a024bc47348da2ccd8dc980d389dacc9d1d33b3412614e88732dc424", size = 6045 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-metrickit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b2/71/82f14e24708d44eb0c53b4fc57224bf5db8fa268c0632974abd6ea4b2e7f/pyobjc_framework_metrickit-10.3.1.tar.gz", hash = "sha256:f0b96fe9da0e26759f38d9e4cdf7d9c8be9c6ba35403bc8e675183a6f81dd0b3", size = 31749 } wheels = [ @@ -3533,27 +3641,27 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fe/ba/3f3e0272354366a6759a0529b32f6fc2f0d21a5071873fd26fc89f304c16/pyobjc_framework_MetricKit-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:58dbfc7b9ae7701a59b9b2a5a5f874a9e393f10b27f39155714d1b49ea725226", size = 8124 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-mlcompute" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/db/9a/405b3091a514670d36d21a9f1a9441555ae3b6cc0e6913765484af1cf52f/pyobjc_framework_mlcompute-10.3.1.tar.gz", hash = "sha256:9ac94b0a9511fedceacda846865daa05358eec5a4bf62be534b69eb4d7aced9b", size = 68347 } wheels = [ { url = "https://files.pythonhosted.org/packages/07/82/1d9ad402910d9def7622c2b85a147364ecb31ad1add4a3ddb64c98f5abaf/pyobjc_framework_MLCompute-10.3.1-py2.py3-none-any.whl", hash = "sha256:e5f8d98ee43fc795f44dab322299cf8957d7e6acb54139cecebfc7f4b2562b6c", size = 6410 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-modelio" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/98/d1/3020a89e0e1145b831351b1e0b34b89b3af7055843384c2a138d3ef4979a/pyobjc_framework_modelio-10.3.1.tar.gz", hash = "sha256:b1da37d10c38c63006d5173b49d18891b2db2c9acdbb6dbd21c73f17c0ccab7e", size = 93075 } wheels = [ @@ -3563,13 +3671,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/29/e4/cb3111bd389461df071ed721734191c1aa9ec9941a7c40783de55d7a9414/pyobjc_framework_ModelIO-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b59069c79c0865334e0036b1938e009addf035bfec36f7d4d871037c14c7accd", size = 21652 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-multipeerconnectivity" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a6/bf/14b2e58b3462ab15fba8fb07fa493da6531d6c8da07382ef2b63e429be4a/pyobjc_framework_multipeerconnectivity-10.3.1.tar.gz", hash = "sha256:eb801d44194eb7eafcb0a21094c4ce78bcf41ed727125b048755838b59de3271", size = 23441 } wheels = [ @@ -3579,39 +3687,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/63/8e/7c070f8cc3a302a3968dbd3318434c40e513440df07d9eb41b522426bc02/pyobjc_framework_MultipeerConnectivity-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:5350d13115b252bf6fa374dba1ef13ffd746b15b16f45d1b77b9231aebdf5b57", size = 12702 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-naturallanguage" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1f/37/a0af80f8bb4ce27b5d6ab5d6bb8a71ea950cbdf81ec73c03b03388d8c572/pyobjc_framework_naturallanguage-10.3.1.tar.gz", hash = "sha256:49f19d0dba34802696a270d690db310ff03f1c85d6fb411734cb13667db90dd9", size = 39154 } wheels = [ { url = "https://files.pythonhosted.org/packages/81/37/7aabe277c3cfd6dc756959e6fa2bacf8e8e1c435b67e33f6a0c799e2a5ae/pyobjc_framework_NaturalLanguage-10.3.1-py2.py3-none-any.whl", hash = "sha256:d0e47fad66bb74fa68b50093500f5cb49d8a772b522f8c92e725f2e65942dd9c", size = 4923 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-netfs" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/90/94/d467f7bc9efdf633f6cb40b83357f1cb91308efea2738f37b7c682e6619a/pyobjc_framework_netfs-10.3.1.tar.gz", hash = "sha256:46466917f7b0aca3772bf4dfd586b583992c60ecd71c39f7d28ff7665d057637", size = 15212 } wheels = [ { url = "https://files.pythonhosted.org/packages/ec/08/1a6effdc97f3eede536e66a7c7e1c50cce644e8d4d5e258a243985997b2a/pyobjc_framework_NetFS-10.3.1-py2.py3-none-any.whl", hash = "sha256:84faa7325c4ecc2f4ad199d8c52cebcb520ad2e7713f356c7a5a849839398d77", size = 3791 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-network" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b7/a2/547e786e3ff87e4facf038b0375d8fd4a48a8f6c69762efc7aac87b2d379/pyobjc_framework_network-10.3.1.tar.gz", hash = "sha256:87a5839d4ab2ae452b4e563bd7a00569557ede4b8cd1eb77c973cdf45fb8f5ab", size = 104030 } wheels = [ @@ -3621,13 +3729,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/6d/04/1a5d7daa7704ac3d096a3c76a3ffde49df5b836a7f6f355e72f95f7fbdd2/pyobjc_framework_Network-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:c665f3dcfb1375835dd0c6ce10079f22be73f92213fc3d48b176d9c67fc221a9", size = 14385 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-networkextension" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/dc/46/1af5ad27f16af7ef97cced31dc70d92cf85c08d1e15a32997f9e40496601/pyobjc_framework_networkextension-10.3.1.tar.gz", hash = "sha256:c5a094862061565ca6d37457db42f55f344ec24dd7604ddf5d72e20ae7f63fdd", size = 130653 } wheels = [ @@ -3637,13 +3745,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d8/df/34dfbcc84a34b3edd4813da0324091f83da64a8d246738903f947c739e94/pyobjc_framework_NetworkExtension-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:1c8ef5fce8846fb3bf459bedf7a31ff0428a9c3184c8b26ced8e322c956e8ec0", size = 14222 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-notificationcenter" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/11/a4/105abbec54e815ab9de653bba08db37524589c369badab6e1a5e3bd598a3/pyobjc_framework_notificationcenter-10.3.1.tar.gz", hash = "sha256:3e6efe0fe6389601bb87086f5585fa7e74b2143236b7d5afd02b617a73656419", size = 21039 } wheels = [ @@ -3653,41 +3761,41 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/57/59/bdf3194bd3693132370f4cc1a002bde09dd248f2a49026e5ec4785970083/pyobjc_framework_NotificationCenter-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:992ea7c86d0330cf10113b829525d74a95d97d0d7245e4e277f75ecbb37b596e", size = 10524 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-opendirectory" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/32/1e/85e8d9ea9ee43a111a6d278c5006a3a58c4573af60ba7932402cb3ca5e84/pyobjc_framework_opendirectory-10.3.1.tar.gz", hash = "sha256:cddc25632eebeb6bf0d886ae0fc919d574e458c597691226ba15bbf134ab51a6", size = 159659 } wheels = [ { url = "https://files.pythonhosted.org/packages/ca/17/74c8d815ddd43d206311baf00237c8a14c4c3cb7ad656ef33afcfe370655/pyobjc_framework_OpenDirectory-10.3.1-py2.py3-none-any.whl", hash = "sha256:7e787e65409aad082faed2ed0c2cd52cccea61702d9c83b6acdcac3fa50a562f", size = 11425 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-osakit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ce/db/2ee141472cb30079b8881d4839f4d46d38bed2e78e04d5ecf44885d05cd7/pyobjc_framework_osakit-10.3.1.tar.gz", hash = "sha256:0af326b831fa29fca11ffe2b641807ad3c233be9eb403e62328fa784528da4ab", size = 18286 } wheels = [ { url = "https://files.pythonhosted.org/packages/f3/37/f644ff0e1013ee25a3c543f4240687f7ab79580df401cafff8e5dfea278c/pyobjc_framework_OSAKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:aaa60e6f455febe45f9be6487c59f11450de81bd7f49a6e4db576a38bcaf1c68", size = 3784 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-oslog" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coremedia", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/11/ba/45a84a9a26608c8dd2d909f8ad8183434c17b1d4071ce910388c80a07637/pyobjc_framework_oslog-10.3.1.tar.gz", hash = "sha256:592c3e50cf824c2c07779771aa0065de2dbb4c615de43e8949b39d19ba04d744", size = 22288 } wheels = [ @@ -3697,13 +3805,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fe/33/8185fa32c8705f1b16b0d91b62ab290159d7611f2cf46db0fea7c8c87703/pyobjc_framework_OSLog-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:cded4c706fcf3fd78ef257ab096f4f8cefc70cca81553d2fae88841aaf5d620d", size = 8054 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-passkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a5/5a/8336d8fe6371e7696235d131d042572156299d6a0c566a5854f127270adc/pyobjc_framework_passkit-10.3.1.tar.gz", hash = "sha256:4c3eea19c1ae3edf6e7858ab815bcd8ecf517a146928ce6a843910729372f010", size = 94853 } wheels = [ @@ -3713,39 +3821,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e8/c3/b1a04f416c25f0f4c194137ba8ce4444a7c0e7f3b42b38b278e3a707ff5e/pyobjc_framework_PassKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d41409ee24eee2318023c3ba23218db152fc262ebcbea9021dc533fe80a73f32", size = 13787 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-pencilkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d2/8e/9152ecf82135f5f6ec94f4b407948cdee9b8f01ead2896613422dbfe8ef1/pyobjc_framework_pencilkit-10.3.1.tar.gz", hash = "sha256:4dfd8e0179be5ecf67b768317a88d86d93df1c8674d422afa14957cf80e6e01f", size = 18784 } wheels = [ { url = "https://files.pythonhosted.org/packages/1b/41/a15fd222e8f9b28ab18440ac3d4c2aca98c640f2e1456dbc018c451c7556/pyobjc_framework_PencilKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:dc05376fbc5887391ff4e778b6f4b2fa20264aac58cd5fe5f47e4930186c1674", size = 3653 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-phase" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-avfoundation", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f8/7c/57e7a130932027f11ce8bfb68e8a6a910b9ec11c8bd4647605d0c6ff1ade/pyobjc_framework_phase-10.3.1.tar.gz", hash = "sha256:5be2ea5d36ea9620f5278f5ad3b02cc243511be3b137aa28b1523e8f6da54f99", size = 43938 } wheels = [ { url = "https://files.pythonhosted.org/packages/82/5b/948fcead87fc9badb4de137829423ce53f1d03a5f8d873e4d0cea01745da/pyobjc_framework_PHASE-10.3.1-py2.py3-none-any.whl", hash = "sha256:eec5a38983d65a4cf022dd01dc6f290ec163399e79592203443b4115ea3c8510", size = 6233 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-photos" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4f/e3/764707657dc2ee986510ac137dfcb98ca3498fa21ed7c79e711df3b85736/pyobjc_framework_photos-10.3.1.tar.gz", hash = "sha256:8d538c399720062523694f7669aa82dcb75a7b192fb4aca93cf782d04e4c39be", size = 74176 } wheels = [ @@ -3755,13 +3863,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/17/25/83a32b4743b63c7262c476bd0acbca8304e942483e599acade70aa0dc345/pyobjc_framework_Photos-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:50710703d18d0b13c48e02ab4edcca72a67ee20aac2a75664bfb725c8cb3a677", size = 12687 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-photosui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/aa/34/6ee322114383d37c4921fc15e41ba4595347f0b108e14d6232e540d77c5e/pyobjc_framework_photosui-10.3.1.tar.gz", hash = "sha256:e9eb961c6be1f3e00d76cc0a8ec15b50ac0692bd5b5c86268ad08f6d09cf390d", size = 38914 } wheels = [ @@ -3771,39 +3879,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/65/f2/df518ac867baff73fbf91f7a9e97165065f9db96785c45b2bda6d68d5774/pyobjc_framework_PhotosUI-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:a756c3bbf945ceaa7d184c41053c2a9c1a89b32ffcdf752664b1180927b22cb2", size = 12506 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-preferencepanes" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8a/56/da2d75cf4900a62cafde27d875bbe0dc0e9c3624b6d4c08adc69d9336033/pyobjc_framework_preferencepanes-10.3.1.tar.gz", hash = "sha256:eef150416a39a0109a8a37e9978ac4a55ad0b125ef6053a7431524ede5c69783", size = 25330 } wheels = [ { url = "https://files.pythonhosted.org/packages/78/54/e2d55873233287481d11f9d92254e0fc8a86d2c37c062186c1867d41c7a6/pyobjc_framework_PreferencePanes-10.3.1-py2.py3-none-any.whl", hash = "sha256:319b58b6c8f876f67e879b3a4f74afd6d892aa43a7f9ef4320819265b281c9e5", size = 4384 }, ] -[[distribution]] -name = "pyobjc-framework-pubsub" -version = "10.3.1" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/ad/94/7126b622790d16a422589938b97f8c7c13a0724d9b9c8bed7badd8016d01/pyobjc_framework_pubsub-10.3.1.tar.gz", hash = "sha256:d123e75288c2f9d785ed1c4d92a96e5118c4b6f1cd9c55605eb4b4a74c2e36f4", size = 15716 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/91/ad/87b0141019472292be66bfe2d867c8aae2324e3eedde95312a39689e6b50/pyobjc_framework_PubSub-10.3.1-py2.py3-none-any.whl", hash = "sha256:dd8bc334b3acbdd82163d511bc71af7addc98dfaf473736545487f3168836dcd", size = 4793 }, -] - -[[distribution]] +[[package]] name = "pyobjc-framework-pushkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/30/d6/2fec9c42a76466902b14afeea7a9c8cc2c90aeafd3f3dbe72af474681dc5/pyobjc_framework_pushkit-10.3.1.tar.gz", hash = "sha256:cc4da5382cf48c29637af1c633490203358a6ab0c76f0c006079cf144eeb9568", size = 19167 } wheels = [ @@ -3813,13 +3908,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/21/ab/c15351016775f0134b3d500f599d07fb20fffae7ec85c089e1ee79f047c9/pyobjc_framework_PushKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:ee90959fc7b171930cffdf07cb7865d56a2cb4b723c5826ccf95d6e865dee4bd", size = 8630 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-quartz" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f7/a2/f488d801197b9b4d28d0b8d85947f9e2c8a6e89c5e6d4a828fc7cccfb57a/pyobjc_framework_quartz-10.3.1.tar.gz", hash = "sha256:b6d7e346d735c9a7f147cd78e6da79eeae416a0b7d3874644c83a23786c6f886", size = 3775947 } wheels = [ @@ -3828,27 +3923,27 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ce/7a/78b512061af37a4466607143a9876192f04c5810b16e4cb097fbbfa02dc5/pyobjc_framework_Quartz-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:00a0933267e3a46ea4afcc35d117b2efb920f06de797fa66279c52e7057e3590", size = 226586 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-quicklookthumbnailing" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/29/04/ef2db0a73af5b2530de728529f5d637bbe5f09bf4165493db0ab3df2018b/pyobjc_framework_quicklookthumbnailing-10.3.1.tar.gz", hash = "sha256:ee26be78df9ce46ffa6f971f4ce167a0e98f38167aeb86cfc1b41270f15c96a3", size = 15534 } wheels = [ { url = "https://files.pythonhosted.org/packages/bb/d2/6c199cf69d5402cd4317600e7a4f925964a2eb9df44e4a09437af5dbf037/pyobjc_framework_QuickLookThumbnailing-10.3.1-py2.py3-none-any.whl", hash = "sha256:e5095c0ad8cf1f91a6ed9aa5c4fb7c9b1da122d495ce131bae8d7faa06da9505", size = 3814 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-replaykit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5b/37/dbadcb487150f4ea1a691c83d09f1ed58463bed6b4fa54dca6aeb1584d06/pyobjc_framework_replaykit-10.3.1.tar.gz", hash = "sha256:21762c8674b629fb670c3cbd515c593f1b5f98ee24ee4834a09055cb08849068", size = 23417 } wheels = [ @@ -3858,13 +3953,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/5a/7f/0fcd8020fb8b29e31c42ce0a672b58c4e3b41d8a587ce621e06a68d89b0a/pyobjc_framework_ReplayKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:22ca748ae8325e41e0526f13822d2c477ab879cb2d454eee1db47ca91353c986", size = 10047 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-safariservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/69/63/c12192ed8b5a08cc5313aef6d4e6d86d9d17171d4325a7f6e2f8c0da7a19/pyobjc_framework_safariservices-10.3.1.tar.gz", hash = "sha256:9c5278576e7c28c3d93e74ebe5d39d07c5c91572ddf03ea01cc45d9a06dc8d0a", size = 29436 } wheels = [ @@ -3874,14 +3969,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a7/71/2dcd9ba1b7bd51619db281ff74cbda5ab1a49225bebb8e19ff5ab0556eda/pyobjc_framework_SafariServices-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:aaba0ea92410820d94fef0b93d337478f0e416967cb2aa4e667dd4d1bb561c1e", size = 7461 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-safetykit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d8/db/1d099ed2b3655caacad70315a6789b47277f9939f73d4f13810bf27f9e29/pyobjc_framework_safetykit-10.3.1.tar.gz", hash = "sha256:8421be801ce29053e67a2c91673913562c3ad9d4bb1fbaa934a3a365d8bff12d", size = 19035 } wheels = [ @@ -3891,14 +3986,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/58/50/d8bbb45c931ec9c5205bc1fb3d03336e6c992b90b9444b3c6ed6be0069c7/pyobjc_framework_SafetyKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:ac700aa2cbddc8a31626815886e42d0d1591572914c2b15df2dd07871ee84568", size = 8324 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-scenekit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/23/cb/0451b9463cc1d19eef523dfc6098c5d774cbd5f4cae9fbc6884b17cd5cd9/pyobjc_framework_scenekit-10.3.1.tar.gz", hash = "sha256:99cf0db3055d9bae0a8643400e528a8c012235db8ee6a1864ea0b03a0854c9d0", size = 155276 } wheels = [ @@ -3908,14 +4003,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/44/17/6c72f136bdd00e2bb7093247db6be90117f9a0512cc3a15fa56073886843/pyobjc_framework_SceneKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:2984a543221190547bff603a6a59c931cda7099b91ac7412e11c962e8f6c3bc1", size = 33117 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-screencapturekit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coremedia", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d4/20/51dbb697dc5d3bc522771afa375e05370e6357b49dacf1bafe7dae37908f/pyobjc_framework_screencapturekit-10.3.1.tar.gz", hash = "sha256:cb1a2e746e0f98ea14a11ea35d059d38587340beeeb905812085e2c7ceb14e0c", size = 34829 } wheels = [ @@ -3924,13 +4019,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/cd/3d/17cb4d822faf26efe04e2f0749783abeaddb86529c1af59ec8f8270deccb/pyobjc_framework_ScreenCaptureKit-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:4d8e280a076e7bc40eaa9730f97da84421b891c30f6e3fdea4f6c30bdb298243", size = 11368 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-screensaver" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/dc/7c/55374bae0be8632e2c76b911af3bcdfd5b5ea417c125d8268f8207c77516/pyobjc_framework_screensaver-10.3.1.tar.gz", hash = "sha256:0bbc5b574f12e95f6f6e48ced40b601e46e560ef6786845c15c57d78e6cd083e", size = 22037 } wheels = [ @@ -3940,26 +4035,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7a/c7/76e8315650b4d90c2ef690480fba37d75dcf5aa1c3fe177238348e6d2e7d/pyobjc_framework_ScreenSaver-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:616ffb4bac2a56108778e33be6fe75b28f19511157abc411960b72324276635d", size = 8005 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-screentime" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/38/a5/b2b9c57eb364ccc1074442ce956b0052f71e903b7b944a93bc4888deb94d/pyobjc_framework_screentime-10.3.1.tar.gz", hash = "sha256:351179d5bf951aa754c72f50ba8785212adf1b26abe10149c750fafd0a3108ae", size = 13365 } wheels = [ { url = "https://files.pythonhosted.org/packages/b5/00/475bee668c55ca6d39464bb80ffb7e8c3012b027183e6d91c675b4b5e5aa/pyobjc_framework_ScreenTime-10.3.1-py2.py3-none-any.whl", hash = "sha256:d4f8a0784dc7d7060dadae2e4b5aae5e1afe8bbf453ce49cbb1860b8920114c3", size = 3403 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-scriptingbridge" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/10/45/ef1ae83f84555c3cf7ba18e53be9ace9f4225e56b852d7f5d79b5c516d4f/pyobjc_framework_scriptingbridge-10.3.1.tar.gz", hash = "sha256:6bfb45efd0a1cda38a37154afe69f86ea086d5cbdfbc33b3e31c0bda97537fe9", size = 20828 } wheels = [ @@ -3969,26 +4064,26 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/51/f3/8417c284db5b68f958d8421b331cb3d4ab4caf85a7af8110dede55b084aa/pyobjc_framework_ScriptingBridge-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:90022f44f2bf0563bf5a75669198b9d778f76ece719f237750e9c5fcb00a601d", size = 8510 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-searchkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreservices", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] sdist = { url = "https://files.pythonhosted.org/packages/85/74/1ee0012987c203f6776b7ca3da12b68623d9861c96ddc9575809c38864bc/pyobjc_framework_searchkit-10.3.1.tar.gz", hash = "sha256:7efb76b7af9d8f0f08efb91543f4dba0b00261ed41abb121ada80175cc82d65d", size = 30449 } wheels = [ { url = "https://files.pythonhosted.org/packages/a8/40/9c3231a96b55776338005ec60f278488111f4093af8bc9f1c7f17696406e/pyobjc_framework_SearchKit-10.3.1-py2.py3-none-any.whl", hash = "sha256:48ec776603e350405c7311f29d5941e0e9d6b6a75e2aec69e0acd28be0979905", size = 3320 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-security" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/20/db/3fa2a151c53f2d87d9da725948d33f8bb4c7f36d6cb468411ae4b46ad474/pyobjc_framework_security-10.3.1.tar.gz", hash = "sha256:0d4e679a8aebaef9b54bd24e2fe2794ad5c28d601b6d140ed38370594bcb6fa0", size = 252496 } wheels = [ @@ -3997,28 +4092,28 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/5a/32/4d233b667ae2b7a9106c4a7ebb2552801cc4474c66f6a23750d13f60e289/pyobjc_framework_Security-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6120e91282985bcec3b44c1bc4f9c26d40cd07b4ac3dc81f745d73c13f8b5523", size = 41021 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-securityfoundation" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-security", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/40/d6/908dcceb7cd5dcfa3ff265dfcb945a8707256f7ab09ee709d86cb26ae1d4/pyobjc_framework_securityfoundation-10.3.1.tar.gz", hash = "sha256:414b13acabfae584729cd614e27247d250ec225d31140e8d971aa08536d6150c", size = 12595 } wheels = [ { url = "https://files.pythonhosted.org/packages/93/43/3f0b77bc72a9c419b355cbdaaa4a289ae838f6593421292b790b58512888/pyobjc_framework_SecurityFoundation-10.3.1-py2.py3-none-any.whl", hash = "sha256:c352cde672c9c2afa89575c362a0714e589c118485cec49ba230327e92c8a9a6", size = 3383 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-securityinterface" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-security", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b6/8b/d2dfd658f279fe6d3416b45c5030a65342ded0150ba56e028f6dcc9b38e1/pyobjc_framework_securityinterface-10.3.1.tar.gz", hash = "sha256:cd25f342a2b53cbffd134443506d5e75c96ba7145135debb8932c1252d57269a", size = 31921 } wheels = [ @@ -4028,40 +4123,40 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7e/b1/8bd136570f27057f2a73bb27f67f2ed638169d9660474d77e9b531e821a7/pyobjc_framework_SecurityInterface-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:d913d30d04c9f01679ead33c95ad53dade587995f48c778a6de4d7da239b43e3", size = 10809 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-sensitivecontentanalysis" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ef/3d/7b50fb510374640c7562fc3cc83a75d91bd23f3f53a15579bd0061ffc3bd/pyobjc_framework_sensitivecontentanalysis-10.3.1.tar.gz", hash = "sha256:ac8dd18d77ccc0bb4eb24839cf39da9981db64e53f52b09636e47bd7b3066f84", size = 12006 } wheels = [ { url = "https://files.pythonhosted.org/packages/fc/bc/09d3c469f63366eff7caf148e53bf38a3752178a62a99881a0ef11453549/pyobjc_framework_SensitiveContentAnalysis-10.3.1-py2.py3-none-any.whl", hash = "sha256:6b5cfe771a28300d766ff14ff81313fda946943d54a039d5574478a070933e03", size = 3451 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-servicemanagement" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ec/de/f60506eef312ea3cbd5eacd1308bfb7e68f8d1a032573840f46b7de3a122/pyobjc_framework_servicemanagement-10.3.1.tar.gz", hash = "sha256:d048a803ad34c997dcc99ba778fca9d91cc5adfa1d115202e4bf22d9b04fd92c", size = 15746 } wheels = [ { url = "https://files.pythonhosted.org/packages/09/ed/72cbba493d3e6d17127f39f1436b12248a812ca9714fdcf02f6834e7bb93/pyobjc_framework_ServiceManagement-10.3.1-py2.py3-none-any.whl", hash = "sha256:6b7ca0de9cf74439df0947aae29f5f31d58eeacb0ff55e1465faed540d31de4b", size = 4927 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-sharedwithyou" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-sharedwithyoucore", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-sharedwithyoucore" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a2/c8/261b3ae7063550b157fd33e9931c53007e4b7ff209a6d5a393b301af67c3/pyobjc_framework_sharedwithyou-10.3.1.tar.gz", hash = "sha256:7e35b631bc77b040151515e4fee9c8f47bc313924fc3e5970e940f1343db039b", size = 27924 } wheels = [ @@ -4071,13 +4166,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/4f/33/bb8c76ac26329e37b22386d238cd97683494e5e8f875c0a6682b7ea524c6/pyobjc_framework_SharedWithYou-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:bc37e1c86f460095085a5060149ca013d4dcb9b54337887bff86a2e07302c0f1", size = 9084 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-sharedwithyoucore" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/58/ba/09d6cfb51167b14711d2a2526d69994566eec101578af0e39b84a4794e5b/pyobjc_framework_sharedwithyoucore-10.3.1.tar.gz", hash = "sha256:e4768b7fdb18730e225bbebc9c9f9acfa7e44e648875816aff8c7e7f0e82afbf", size = 24331 } wheels = [ @@ -4087,13 +4182,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e5/90/aaf3a46470effa512fd7aa9f8cd35ed1ce861b785c8dc5f5519052a249c0/pyobjc_framework_SharedWithYouCore-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:1e51f315b5b16b340a1a12d4a0f3244f1925f14c9e148ca4dfdcfad6baa7ee5a", size = 8886 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-shazamkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/07/d7/5cf2157fd163084d75d1cf9cf2de774d373387162a7b03c19cbcd193f22f/pyobjc_framework_shazamkit-10.3.1.tar.gz", hash = "sha256:deef11a43e773b876df31eeadbfc447892fda0607e314ca2afb2c012284cfa32", size = 22923 } wheels = [ @@ -4102,39 +4197,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d0/23/2139cd328324253b27384d99a50232ee930ac33fb829cfad3f7e29283455/pyobjc_framework_ShazamKit-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:4356bdcb9ca50da243b9d79da27851b799483865072f7c86a8a9674300d31819", size = 8592 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-social" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/94/a8/c5a8ea9eea5ec096e03fcda22f3bf5077710a988dbcdbc543afed7478d34/pyobjc_framework_social-10.3.1.tar.gz", hash = "sha256:d1303cf3860ad02a8795c099e17888923505a9c45be407da50721a9a8a5b2efd", size = 13749 } wheels = [ { url = "https://files.pythonhosted.org/packages/89/bc/aa8ad14fc35f7a08fdc78757bfb341f3f4da9c6c8036201777d5f17b5ca7/pyobjc_framework_Social-10.3.1-py2.py3-none-any.whl", hash = "sha256:f83617c07db7c8bd15b3b9e0878ab2b6a286dcbd9a8c7f451da204f75db880e9", size = 4065 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-soundanalysis" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cc/23/bb9bc28f3d96e1316ac257b6b0605bcefb4b38879b9594272bbc9505e341/pyobjc_framework_soundanalysis-10.3.1.tar.gz", hash = "sha256:faa533644231f99dbdc2fcc3ecb9181c5df4f4dc68d42856729214021c83c881", size = 15578 } wheels = [ { url = "https://files.pythonhosted.org/packages/5a/f6/350c7b3e9ceba976a4669c87b86cf378918cb6938a6083cc16aeb271c81b/pyobjc_framework_SoundAnalysis-10.3.1-py2.py3-none-any.whl", hash = "sha256:ef67207ff4045e5db37f017bdcd07d4b42464c86fe6c3b56524f6f22a9cde216", size = 3789 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-speech" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e6/8c/cc25b4267f884139b9677ea3fed8a8b99c423ef3f72dcc35eae6a01e4007/pyobjc_framework_speech-10.3.1.tar.gz", hash = "sha256:5b77b1d1ced0d1ad7244037b865dda2b83e8f9562d76d1e9fa4fea3b89e437b8", size = 29979 } wheels = [ @@ -4144,14 +4239,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0d/f9/ae6eb7a2c72f15820ab8bbbf3b57be719fb491fe6523a7e9d1700c613b82/pyobjc_framework_Speech-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:2294b60e1ab59b1340b820e6fee67766a959edd580d73e3b938f15653805d64c", size = 9555 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-spritekit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/fc/a3/037c63ce21d3a01d1d3c891b17979c5c1ce13a0893c97848bf2eb3e30442/pyobjc_framework_spritekit-10.3.1.tar.gz", hash = "sha256:2c11f35f48302f487c51ba8030f5cf79493a9dc0993dd901016ae4b8d8047c8b", size = 95557 } wheels = [ @@ -4160,13 +4255,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/fb/ef/f237933784a49e693948cbe0926e132e886d7f0b3009eb92b9d822b829cb/pyobjc_framework_SpriteKit-10.3.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a1f0537bc0331cca58cc50307f3b114ab8bfd51576df3038b6037353aa77085f", size = 17833 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-storekit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/bb/42/e0ebe600ca0572fea164c2308bdd8866cb09167ef1617ed66d5c9a9a6026/pyobjc_framework_storekit-10.3.1.tar.gz", hash = "sha256:913b4aad7dc31df7d8011c54a695da65cc57819f4b48c98abaed4e6d9ff7d323", size = 63667 } wheels = [ @@ -4176,27 +4271,27 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2b/e7/49a1b2b3ef3a16ea29110db454f7428e78472aacba230e4d96c81e18451c/pyobjc_framework_StoreKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:2b5848f0e08b42dd4dabe5822b436b904a697e923f529ccaad910dfb822b2b9d", size = 12544 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-symbols" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d7/2b/e32921c7f2e00ba41fdd6befc0f7aabf17bc4c136f2b6a0cf4f44939940e/pyobjc_framework_symbols-10.3.1.tar.gz", hash = "sha256:3e3f35ef3646b5f9c0653d9dbf5693cf87de3df04420cb2679dad74c75965d18", size = 11785 } wheels = [ { url = "https://files.pythonhosted.org/packages/97/bb/f4a01bec12bc1c9dfe86b0428d39a5e9d5614e0f433b5eda42af43d3d1c0/pyobjc_framework_Symbols-10.3.1-py2.py3-none-any.whl", hash = "sha256:6e171da5af2612e186cc4cf896ad7f2672c021a1fc18bc8ef49b79c4c831202d", size = 2958 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-syncservices" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coredata", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coredata" }, ] sdist = { url = "https://files.pythonhosted.org/packages/77/eb/6b73844bc7a4f964128cde7fffbe4243b62c691626b4b101337b6ac7caff/pyobjc_framework_syncservices-10.3.1.tar.gz", hash = "sha256:1cd5e3eaf85a11996184afad1da47037cd921e302ccb35fe388b19f91a685669", size = 49572 } wheels = [ @@ -4206,13 +4301,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/84/e0/e72454fbef0749ba98e77ac91a5fc055abadec202ee75b1d95001fcf0fab/pyobjc_framework_SyncServices-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:b9b7bc58b04654172968cdc1cfe74b43ca0ad2e03c24c7921234a57be2c22985", size = 14329 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-systemconfiguration" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1f/34/4a8a79ae382296533cf0aa51377f53d9157aa41484c83a506d9dc43fc9e1/pyobjc_framework_systemconfiguration-10.3.1.tar.gz", hash = "sha256:1bf6ffe98faa4e208bf594c857ba23cd56fe404bc579188ff53b704844d9c402", size = 124143 } wheels = [ @@ -4222,13 +4317,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/17/8e/fc0b787b8b68b1baf1f1881150f6b6d8d1b5480cf1f22ea063260a057ac9/pyobjc_framework_SystemConfiguration-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:4e8816524cbb6c6ea9e1c596fc9a16c91f2063eba394135be9437bdbd469e125", size = 21680 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-systemextensions" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/dd/d2/eab93a69f95c757104112cb0bce3e1fc70de59ca47ff0c60d180f306819f/pyobjc_framework_systemextensions-10.3.1.tar.gz", hash = "sha256:34412e75c95a585d222ea23efc3eba436210ec0345cec6c7dc78d16e027d03e1", size = 19844 } wheels = [ @@ -4238,39 +4333,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9d/79/5cf9fad837bb20f221ac981e3f300eecb9a92d154bc53685173654baee30/pyobjc_framework_SystemExtensions-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:6561876b2fd5c40620073fae9b924f2d8e0110e8573756ffc9521e4fbc825249", size = 9091 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-threadnetwork" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/dc/6c/c502594ac550436bb8d989b18734eeabd5ce189c2ebb1f4895e3e00d424d/pyobjc_framework_threadnetwork-10.3.1.tar.gz", hash = "sha256:1038210a8e5dfa86aefd10894563913e767e95d1c1bd4333ae5f9c6cabbb3ce9", size = 12639 } wheels = [ { url = "https://files.pythonhosted.org/packages/21/d0/bcc8756d01a1d4f400148f67123a7238429be7c2ddb95f94d15beec8372f/pyobjc_framework_ThreadNetwork-10.3.1-py2.py3-none-any.whl", hash = "sha256:95ddbed8a114cc1f05db613bb53247465ec48ccaad2b56f5da466317808fc32b", size = 3377 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-uniformtypeidentifiers" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1f/54/10c56c741e7c95ee4dd8db06afac5e59722e5372e35f3c5a3e7c2954c746/pyobjc_framework_uniformtypeidentifiers-10.3.1.tar.gz", hash = "sha256:1985fee7e1f1157db36f3c19ee0ad273677eeff10467f575086246bbeffcdf50", size = 18476 } wheels = [ { url = "https://files.pythonhosted.org/packages/37/5c/48f1c942fa870439598e296eb2136fc5cec3f4a6e08bff25f727dc5e9bb8/pyobjc_framework_UniformTypeIdentifiers-10.3.1-py2.py3-none-any.whl", hash = "sha256:8bd1516ccec1807e2ad92a071242d83e9d1eda08ddbfae04dacc30d76c3d734c", size = 4467 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-usernotifications" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/12/d2/32432d2b579ca393f65f7ae7b53cf887f2efda861c4e1b372428f65dd4bf/pyobjc_framework_usernotifications-10.3.1.tar.gz", hash = "sha256:ddb5de88fb659c2241429b6408ddcabbfc0c2c9e4a7f5f543a6fab1c4953403b", size = 45987 } wheels = [ @@ -4280,42 +4375,42 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f7/46/188efc812446f32793673d1d3d000e037052373e2bb19e0a3e5d1036b53b/pyobjc_framework_UserNotifications-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:59294fa6110778de145c9299c220990d057a6a171d37ab5d8a6ab1780bf7888f", size = 10049 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-usernotificationsui" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-usernotifications", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-usernotifications" }, ] sdist = { url = "https://files.pythonhosted.org/packages/df/10/a525f13919955d653fd431f527974e2604b0b8727c886de1ec7e2bf34189/pyobjc_framework_usernotificationsui-10.3.1.tar.gz", hash = "sha256:80390b5361bb6014dc32d0afbf581280e7762a4f67460a736f461f613d397094", size = 13288 } wheels = [ { url = "https://files.pythonhosted.org/packages/17/4b/1a198d4d8907d83f4334d34dae76572e18362391ee0644c9a5bc002980e7/pyobjc_framework_UserNotificationsUI-10.3.1-py2.py3-none-any.whl", hash = "sha256:bc6cb92a6ac947e8fe9685f3c1964c5a9f98e576b936b0bbff8c528f47f976d2", size = 3522 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-videosubscriberaccount" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c8/a6/41d6afaa800bf8839c45642b60d7fa13a0e292d477762c33ce22ba1c0aa6/pyobjc_framework_videosubscriberaccount-10.3.1.tar.gz", hash = "sha256:f62509e976b805bc76ff5928444677ac542b52dd9f7781ac0731d7c4b22bed96", size = 23793 } wheels = [ { url = "https://files.pythonhosted.org/packages/88/38/a9e721db0fa383eeabaadd6c6762ea33d6f50a25c22b70ee82c31d536e66/pyobjc_framework_VideoSubscriberAccount-10.3.1-py2.py3-none-any.whl", hash = "sha256:4b489f0007dce8ea17f37316175dac2768cd173a4d4c7a1d5f87fb3991c1e518", size = 4295 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-videotoolbox" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coremedia", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/65/e4/435561672801cb29a398b208e75e6823e6c369027cd51f0774f3b24f2baf/pyobjc_framework_videotoolbox-10.3.1.tar.gz", hash = "sha256:7ebc281523b2b37aff17ce6eabd0c81081864b3e3e4a83ae72b18fd70c57c521", size = 66253 } wheels = [ @@ -4325,13 +4420,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a6/6c/51641d571758869feac26a48f625be1bcfe8ef3e30badcc36823baffe486/pyobjc_framework_VideoToolbox-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:7d4fb38f95e91f62d14b05fafcc6197775e9eaf4e5b698bc1fb313756f59b10d", size = 12811 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-virtualization" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2e/d1/427065aab5570855228fe0bc3d387fcc4c76e18538c28c5fc2497b0f75f2/pyobjc_framework_virtualization-10.3.1.tar.gz", hash = "sha256:8348ddef18eb943d151e5b5977e4d410012ee2e3f6048c16f7cfe0c1a73536cb", size = 61591 } wheels = [ @@ -4341,15 +4436,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9e/6a/732e29e221584680c669a2cf5e0c148832ef3643588cbf8ba1ec971be773/pyobjc_framework_Virtualization-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:6e5e6645e31acd07d30b1607c4cdaf0ae0e4d8223471a8a089004c2deb6fdea5", size = 12231 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-vision" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-coreml", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-quartz", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreml" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7c/55/ff278351cb47f939a932dc5d9d80a8a0d51a427e27e0419833d49219e757/pyobjc_framework_vision-10.3.1.tar.gz", hash = "sha256:aa071656d395afc2d624600a9f30d6a3344aa747bf37f613ff3972158c40881c", size = 108532 } wheels = [ @@ -4359,13 +4454,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0c/c8/9c6e715b310613aff7612d0b70588cca53e066b577f69db5d66d62e147b9/pyobjc_framework_Vision-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:4302e2c5f68c9667ecd4273809cbc4611af6368b123d69596e5b088f1b1aa16b", size = 17614 }, ] -[[distribution]] +[[package]] name = "pyobjc-framework-webkit" version = "10.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyobjc-framework-cocoa", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/15/6b/50c1000354e9de966a150b4a41c291c83517eec9bd162f43ea4e55444d64/pyobjc_framework_webkit-10.3.1.tar.gz", hash = "sha256:7ad9f4eb91a6dff39848d9c2ab71f170aeab4b6396bcec8e5a780739f9be4222", size = 610874 } wheels = [ @@ -4375,14 +4470,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/77/5a/c9620198d192abc6e8e694301507a3e6c8c76f4d3aac3bac24414f807c95/pyobjc_framework_WebKit-10.3.1-cp36-abi3-macosx_11_0_universal2.whl", hash = "sha256:c8e3334978a1bd927ea14ed73f56d6741561a69d31d082d2b23d1b48446917c8", size = 44697 }, ] -[[distribution]] +[[package]] name = "pyogrio" version = "0.9.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "certifi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "certifi" }, + { name = "numpy" }, + { name = "packaging" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4e/09/a13ffa71f617f3c76f31984bc4fc237aede9988d89056b278efcb97f6fb0/pyogrio-0.9.0.tar.gz", hash = "sha256:6a6fa2e8cf95b3d4a7c0fac48bce6e5037579e28d3eb33b53349d6e11f15e5a8", size = 352526 } wheels = [ @@ -4398,14 +4493,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c3/fa/45efa8c96744ddd92c3ce3a80ddba8512954cc7c5407876e2ff2ffea0c10/pyogrio-0.9.0-cp312-cp312-win_amd64.whl", hash = "sha256:796e4f6a4e769b2eb6fea9a10546ea4bdee16182d1e29802b4d6349363c3c1d7", size = 15905657 }, ] -[[distribution]] +[[package]] name = "pyopencl" version = "2024.2.7" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "platformdirs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytools", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, + { name = "platformdirs" }, + { name = "pytools" }, ] sdist = { url = "https://files.pythonhosted.org/packages/92/68/a26269be1ba101b740a7b47d81032cf71c50a8700cc71ab2c49f0fcccec9/pyopencl-2024.2.7.tar.gz", hash = "sha256:6ae4458a959b6ad9c138fb711a52c4d57c2c2f798eb3aecc4c26830cb2726140", size = 470964 } wheels = [ @@ -4421,19 +4516,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/68/27/2078a4990e45e29b1fb09feb8ec0310e965ef0333e59174882107a813a1e/pyopencl-2024.2.7-cp312-cp312-win_amd64.whl", hash = "sha256:59565d08cb03e03e6c63582dba849472846254465ba8ae532ff87aec0c41f4ea", size = 489398 }, ] -[[distribution]] +[[package]] name = "pyopenssl" version = "24.2.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cryptography", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "cryptography" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5d/70/ff56a63248562e77c0c8ee4aefc3224258f1856977e0c1472672b62dadb8/pyopenssl-24.2.1.tar.gz", hash = "sha256:4247f0dbe3748d560dcbb2ff3ea01af0f9a1a001ef5f7c4c647956ed8cbf0e95", size = 184323 } wheels = [ { url = "https://files.pythonhosted.org/packages/d9/dd/e0aa7ebef5168c75b772eda64978c597a9129b46be17779054652a7999e4/pyOpenSSL-24.2.1-py3-none-any.whl", hash = "sha256:967d5719b12b243588573f39b0c677637145c7a1ffedcd495a487e58177fbb8d", size = 58390 }, ] -[[distribution]] +[[package]] name = "pyparsing" version = "3.1.2" source = { registry = "https://pypi.org/simple" } @@ -4442,24 +4537,24 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9d/ea/6d76df31432a0e6fdf81681a895f009a4bb47b3c39036db3e1b528191d52/pyparsing-3.1.2-py3-none-any.whl", hash = "sha256:f9db75911801ed778fe61bb643079ff86601aca99fcae6345aa67292038fb742", size = 103245 }, ] -[[distribution]] +[[package]] name = "pyperclip" version = "1.9.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/30/23/2f0a3efc4d6a32f3b63cdff36cd398d9701d26cda58e3ab97ac79fb5e60d/pyperclip-1.9.0.tar.gz", hash = "sha256:b7de0142ddc81bfc5c7507eea19da920b92252b548b96186caf94a5e2527d310", size = 20961 } -[[distribution]] +[[package]] name = "pyprof2calltree" version = "1.4.5" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/ca/2a/e9a76261183b4b5e059a6625d7aae0bcb0a77622bc767d4497148ce2e218/pyprof2calltree-1.4.5.tar.gz", hash = "sha256:a635672ff31677486350b2be9a823ef92f740e6354a6aeda8fa4a8a3768e8f2f", size = 10080 } -[[distribution]] +[[package]] name = "pyproj" version = "3.6.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "certifi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "certifi" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7d/84/2b39bbf888c753ea48b40d47511548c77aa03445465c35cc4c4e9649b643/pyproj-3.6.1.tar.gz", hash = "sha256:44aa7c704c2b7d8fb3d483bbf75af6cb2350d30a63b144279a09b75fead501bf", size = 225131 } wheels = [ @@ -4477,12 +4572,12 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c7/f3/2f32fe143cd7ba1d4d68f1b6dce9ca402d909cbd5a5830e3a8fa3d1acbbf/pyproj-3.6.1-cp312-cp312-win_amd64.whl", hash = "sha256:7a27151ddad8e1439ba70c9b4b2b617b290c39395fa9ddb7411ebb0eb86d6fb0", size = 6079779 }, ] -[[distribution]] +[[package]] name = "pyqt5" version = "5.15.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyqt5-sip", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyqt5-sip" }, ] sdist = { url = "https://files.pythonhosted.org/packages/28/6c/640e3f5c734c296a7193079a86842a789edb7988dca39eab44579088a1d1/PyQt5-5.15.2.tar.gz", hash = "sha256:372b08dc9321d1201e4690182697c5e7ffb2e0770e6b4a45519025134b12e4fc", size = 3265445 } wheels = [ @@ -4490,7 +4585,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/91/cf/cc705497cdae04c3c0bc34f94b91e31b6585bb65eb561f18473c998caae1/PyQt5-5.15.2-5.15.2-cp35.cp36.cp37.cp38.cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:29889845688a54d62820585ad5b2e0200a36b304ff3d7a555e95599f110ba4ce", size = 68328841 }, ] -[[distribution]] +[[package]] name = "pyqt5-sip" version = "12.15.0" source = { registry = "https://pypi.org/simple" } @@ -4506,7 +4601,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/aa/c2/c07c531fe5a6124d91942c48a85ff4e14918766cd37819f7841cf2debabb/PyQt5_sip-12.15.0-cp312-cp312-win_amd64.whl", hash = "sha256:24a1d4937332bf0a38dd95bb2ce4d89723df449f6e912b52ef0e107e11fefac1", size = 57922 }, ] -[[distribution]] +[[package]] name = "pyreadline3" version = "3.4.1" source = { registry = "https://pypi.org/simple" } @@ -4515,22 +4610,22 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/56/fc/a3c13ded7b3057680c8ae95a9b6cc83e63657c38e0005c400a5d018a33a7/pyreadline3-3.4.1-py3-none-any.whl", hash = "sha256:b0efb6516fd4fb07b45949053826a62fa4cb353db5be2bbb4a7aa1fdd1e345fb", size = 95203 }, ] -[[distribution]] +[[package]] name = "pyrect" version = "0.2.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/cb/04/2ba023d5f771b645f7be0c281cdacdcd939fe13d1deb331fc5ed1a6b3a98/PyRect-0.2.0.tar.gz", hash = "sha256:f65155f6df9b929b67caffbd57c0947c5ae5449d3b580d178074bffb47a09b78", size = 17219 } -[[distribution]] +[[package]] name = "pyscreeze" version = "0.1.30" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pillow", marker = "python_version == '3.11'" }, + { name = "pillow", marker = "python_full_version < '3.12'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/88/f5/754a6f29a25c7ec375a2e2468ceb83926856b1f0532abd9ec7720ab26b30/PyScreeze-0.1.30.tar.gz", hash = "sha256:74098ad048e76a6231dcfa6243343af94459b8c829f9ccb7a44a5d3b147a67d1", size = 27789 } -[[distribution]] +[[package]] name = "pyserial" version = "3.5" source = { registry = "https://pypi.org/simple" } @@ -4539,184 +4634,184 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/07/bc/587a445451b253b285629263eb51c2d8e9bcea4fc97826266d186f96f558/pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0", size = 90585 }, ] -[[distribution]] +[[package]] name = "pytest" version = "8.3.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "colorama", marker = "sys_platform == 'win32'" }, - { name = "iniconfig", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "packaging", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pluggy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "iniconfig" }, + { name = "packaging" }, + { name = "pluggy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b4/8c/9862305bdcd6020bc7b45b1b5e7397a6caf1a33d3025b9a003b39075ffb2/pytest-8.3.2.tar.gz", hash = "sha256:c132345d12ce551242c87269de812483f5bcc87cdbb4722e48487ba194f9fdce", size = 1439314 } wheels = [ { url = "https://files.pythonhosted.org/packages/0f/f9/cf155cf32ca7d6fa3601bc4c5dd19086af4b320b706919d48a4c79081cf9/pytest-8.3.2-py3-none-any.whl", hash = "sha256:4ba08f9ae7dcf84ded419494d229b48d0903ea6407b030eaec46df5e6a73bba5", size = 341802 }, ] -[[distribution]] +[[package]] name = "pytest-asyncio" version = "0.23.8" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/de/b4/0b378b7bf26a8ae161c3890c0b48a91a04106c5713ce81b4b080ea2f4f18/pytest_asyncio-0.23.8.tar.gz", hash = "sha256:759b10b33a6dc61cce40a8bd5205e302978bbbcc00e279a8b61d9a6a3c82e4d3", size = 46920 } wheels = [ { url = "https://files.pythonhosted.org/packages/ee/82/62e2d63639ecb0fbe8a7ee59ef0bc69a4669ec50f6d3459f74ad4e4189a2/pytest_asyncio-0.23.8-py3-none-any.whl", hash = "sha256:50265d892689a5faefb84df80819d1ecef566eb3549cf915dfb33569359d1ce2", size = 17663 }, ] -[[distribution]] +[[package]] name = "pytest-cov" version = "5.0.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "coverage", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { 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 } wheels = [ { url = "https://files.pythonhosted.org/packages/78/3a/af5b4fa5961d9a1e6237b530eb87dd04aea6eb83da09d2a4073d81b54ccf/pytest_cov-5.0.0-py3-none-any.whl", hash = "sha256:4f0764a1219df53214206bf1feea4633c3b558a2925c8b59f144f682861ce652", size = 21990 }, ] -[[distribution]] +[[package]] name = "pytest-cpp" version = "2.5.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "colorama", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "colorama" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0f/72/6da4fd6ea5afd44e10dbed76ef666c0732e27317a753099bc163f3330a91/pytest-cpp-2.5.0.tar.gz", hash = "sha256:695604baa21bc95291bb4ea7263a7aa960753de57c2d17d224c4652fbcf65cdc", size = 465039 } wheels = [ { url = "https://files.pythonhosted.org/packages/32/d5/b7b5c75dc2e11555898fbec78f88970c43f27439436ac83e65de6afcd2c6/pytest_cpp-2.5.0-py3-none-any.whl", hash = "sha256:137bcaa6487307b4c362245fcd4abf35de64ee85e6375f4d06cd31e6a64f9701", size = 15064 }, ] -[[distribution]] +[[package]] name = "pytest-mock" version = "3.14.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c6/90/a955c3ab35ccd41ad4de556596fa86685bf4fc5ffcc62d22d856cfd4e29a/pytest-mock-3.14.0.tar.gz", hash = "sha256:2719255a1efeceadbc056d6bf3df3d1c5015530fb40cf347c0f9afac88410bd0", size = 32814 } wheels = [ { url = "https://files.pythonhosted.org/packages/f2/3b/b26f90f74e2986a82df6e7ac7e319b8ea7ccece1caec9f8ab6104dc70603/pytest_mock-3.14.0-py3-none-any.whl", hash = "sha256:0b72c38033392a5f4621342fe11e9219ac11ec9d375f8e2a0c164539e0d70f6f", size = 9863 }, ] -[[distribution]] +[[package]] name = "pytest-randomly" version = "3.15.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c9/d4/6e924a0b2855736d942703dec88dfc98b4fe0881c8fa849b6b0fbb9182fa/pytest_randomly-3.15.0.tar.gz", hash = "sha256:b908529648667ba5e54723088edd6f82252f540cc340d748d1fa985539687047", size = 21743 } wheels = [ { url = "https://files.pythonhosted.org/packages/24/d3/00e575657422055c4ea220b2f80e8cc6026ab7130372b7067444d1b0ac10/pytest_randomly-3.15.0-py3-none-any.whl", hash = "sha256:0516f4344b29f4e9cdae8bce31c4aeebf59d0b9ef05927c33354ff3859eeeca6", size = 8685 }, ] -[[distribution]] +[[package]] name = "pytest-repeat" version = "0.9.3" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/86/5e/99365eb229efff0b1bd475886150fc6db9937ab7e1bd21f6f65c1279e0eb/pytest_repeat-0.9.3.tar.gz", hash = "sha256:ffd3836dfcd67bb270bec648b330e20be37d2966448c4148c4092d1e8aba8185", size = 6272 } wheels = [ { url = "https://files.pythonhosted.org/packages/49/a8/0a0aec0c2541b8baf4a0b95af2ba99abce217ee43534adf9cb7c908cf184/pytest_repeat-0.9.3-py3-none-any.whl", hash = "sha256:26ab2df18226af9d5ce441c858f273121e92ff55f5bb311d25755b8d7abdd8ed", size = 4196 }, ] -[[distribution]] +[[package]] name = "pytest-subtests" version = "0.13.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "attrs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "attrs" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/67/fe/e691d2f4ce061a475f488cad1ef58431556affea323dde5c764fd7515a70/pytest_subtests-0.13.1.tar.gz", hash = "sha256:989e38f0f1c01bc7c6b2e04db7d9fd859db35d77c2c1a430c831a70cbf3fde2d", size = 15936 } wheels = [ { url = "https://files.pythonhosted.org/packages/f5/ac/fc132cb88e8f2042cebcb6ef0ffac40017c514fbadf3931e0b4bcb4bdfb6/pytest_subtests-0.13.1-py3-none-any.whl", hash = "sha256:ab616a22f64cd17c1aee65f18af94dbc30c444f8683de2b30895c3778265e3bd", size = 8038 }, ] -[[distribution]] +[[package]] name = "pytest-timeout" version = "2.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/93/0d/04719abc7a4bdb3a7a1f968f24b0f5253d698c9cc94975330e9d3145befb/pytest-timeout-2.3.1.tar.gz", hash = "sha256:12397729125c6ecbdaca01035b9e5239d4db97352320af155b3f5de1ba5165d9", size = 17697 } wheels = [ { url = "https://files.pythonhosted.org/packages/03/27/14af9ef8321f5edc7527e47def2a21d8118c6f329a9342cc61387a0c0599/pytest_timeout-2.3.1-py3-none-any.whl", hash = "sha256:68188cb703edfc6a18fad98dc25a3c61e9f24d644b0b70f33af545219fc7813e", size = 14148 }, ] -[[distribution]] +[[package]] name = "pytest-xdist" version = "3.6.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "execnet", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pytest", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "execnet" }, + { name = "pytest" }, ] sdist = { url = "https://files.pythonhosted.org/packages/41/c4/3c310a19bc1f1e9ef50075582652673ef2bfc8cd62afef9585683821902f/pytest_xdist-3.6.1.tar.gz", hash = "sha256:ead156a4db231eec769737f57668ef58a2084a34b2e55c4a8fa20d861107300d", size = 84060 } wheels = [ { url = "https://files.pythonhosted.org/packages/6d/82/1d96bf03ee4c0fdc3c0cbe61470070e659ca78dc0086fb88b66c185e2449/pytest_xdist-3.6.1-py3-none-any.whl", hash = "sha256:9ed4adfb68a016610848639bb7e02c9352d5d9f03d04809919e2dafc3be4cca7", size = 46108 }, ] -[[distribution]] +[[package]] name = "python-dateutil" version = "2.9.0.post0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "six", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "six" }, ] sdist = { url = "https://files.pythonhosted.org/packages/66/c0/0c8b6ad9f17a802ee498c46e004a0eb49bc148f2fd230864601a86dcf6db/python-dateutil-2.9.0.post0.tar.gz", hash = "sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3", size = 342432 } wheels = [ { url = "https://files.pythonhosted.org/packages/ec/57/56b9bcc3c9c6a792fcbaf139543cee77261f3651ca9da0c93f5c1221264b/python_dateutil-2.9.0.post0-py2.py3-none-any.whl", hash = "sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427", size = 229892 }, ] -[[distribution]] +[[package]] name = "python-xlib" version = "0.33" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "six", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "six" }, ] sdist = { url = "https://files.pythonhosted.org/packages/86/f5/8c0653e5bb54e0cbdfe27bf32d41f27bc4e12faa8742778c17f2a71be2c0/python-xlib-0.33.tar.gz", hash = "sha256:55af7906a2c75ce6cb280a584776080602444f75815a7aff4d287bb2d7018b32", size = 269068 } wheels = [ { url = "https://files.pythonhosted.org/packages/fc/b8/ff33610932e0ee81ae7f1269c890f697d56ff74b9f5b2ee5d9b7fa2c5355/python_xlib-0.33-py2.py3-none-any.whl", hash = "sha256:c3534038d42e0df2f1392a1b30a15a4ff5fdc2b86cfa94f072bf11b10a164398", size = 182185 }, ] -[[distribution]] +[[package]] name = "python3-xlib" version = "0.15" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/ef/c6/2c5999de3bb1533521f1101e8fe56fd9c266732f4d48011c7c69b29d12ae/python3-xlib-0.15.tar.gz", hash = "sha256:dc4245f3ae4aa5949c1d112ee4723901ade37a96721ba9645f2bfa56e5b383f8", size = 132828 } -[[distribution]] +[[package]] name = "pytools" version = "2024.1.10" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "platformdirs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "siphash24", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version < '3.13'" }, + { name = "platformdirs" }, + { name = "siphash24" }, + { name = "typing-extensions", marker = "python_full_version < '3.13'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ee/0f/56e109c0307f831b5d598ad73976aaaa84b4d0e98da29a642e797eaa940c/pytools-2024.1.10.tar.gz", hash = "sha256:9af6f4b045212c49be32bb31fe19606c478ee4b09631886d05a32459f4ce0a12", size = 81741 } wheels = [ { url = "https://files.pythonhosted.org/packages/66/cf/0a6aaa44b1f9e02b8c0648b5665a82246a93bcc75224c167b4fafa25c093/pytools-2024.1.10-py3-none-any.whl", hash = "sha256:9cabb71038048291400e244e2da441a051d86053339bc484e64e58d8ea263f44", size = 88108 }, ] -[[distribution]] +[[package]] name = "pytweening" version = "1.2.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/79/0c/c16bc93ac2755bac0066a8ecbd2a2931a1735a6fffd99a2b9681c7e83e90/pytweening-1.2.0.tar.gz", hash = "sha256:243318b7736698066c5f362ec5c2b6434ecf4297c3c8e7caa8abfe6af4cac71b", size = 171241 } -[[distribution]] +[[package]] name = "pytz" version = "2024.1" source = { registry = "https://pypi.org/simple" } @@ -4725,7 +4820,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9c/3d/a121f284241f08268b21359bd425f7d4825cffc5ac5cd0e1b3d82ffd2b10/pytz-2024.1-py2.py3-none-any.whl", hash = "sha256:328171f4e3623139da4983451950b28e95ac706e13f3f2630a879749e7a8b319", size = 505474 }, ] -[[distribution]] +[[package]] name = "pywin32" version = "306" source = { registry = "https://pypi.org/simple" } @@ -4738,7 +4833,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/1c/43/e3444dc9a12f8365d9603c2145d16bf0a2f8180f343cf87be47f5579e547/pywin32-306-cp312-cp312-win_arm64.whl", hash = "sha256:5821ec52f6d321aa59e2db7e0a35b997de60c201943557d108af9d4ae1ec7040", size = 10388145 }, ] -[[distribution]] +[[package]] name = "pywinbox" version = "0.7" source = { registry = "https://pypi.org/simple" } @@ -4747,65 +4842,77 @@ dependencies = [ { name = "pyobjc", marker = "sys_platform == 'darwin'" }, { name = "python-xlib", marker = "sys_platform == 'linux'" }, { name = "pywin32", marker = "sys_platform == 'win32'" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "typing-extensions" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/b1/37/d59397221e15d2a7f38afaa4e8e6b8c244d818044f7daa0bdc5988df0a69/PyWinBox-0.7-py3-none-any.whl", hash = "sha256:8b2506a8dd7afa0a910b368762adfac885274132ef9151b0c81b0d2c6ffd6f83", size = 12274 }, ] -[[distribution]] +[[package]] name = "pywinctl" version = "0.4" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ewmhlib", marker = "sys_platform == 'linux'" }, - { name = "pymonctl", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pymonctl" }, { name = "pyobjc", marker = "sys_platform == 'darwin'" }, { name = "python-xlib", marker = "sys_platform == 'linux'" }, { name = "pywin32", marker = "sys_platform == 'win32'" }, - { name = "pywinbox", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pywinbox" }, + { name = "typing-extensions" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/ff/53/a7234a6b6d0c5cf295950166498623046422a333d8af79a26552ab40b9a6/PyWinCtl-0.4-py3-none-any.whl", hash = "sha256:8c4a92bd57e35fd280c5c04f048cc822e236abffe2fa17351096b0e28907172d", size = 60338 }, ] -[[distribution]] +[[package]] name = "pyyaml" -version = "6.0.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/cd/e5/af35f7ea75cf72f2cd079c95ee16797de7cd71f29ea7c68ae5ce7be1eda0/PyYAML-6.0.1.tar.gz", hash = "sha256:bfdf460b1736c775f2ba9f6a92bca30bc2095067b8a9d77876d1fad6cc3b4a43", size = 125201 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ec/0d/26fb23e8863e0aeaac0c64e03fd27367ad2ae3f3cccf3798ee98ce160368/PyYAML-6.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6965a7bc3cf88e5a1c3bd2e0b5c22f8d677dc88a455344035f03399034eb3007", size = 187867 }, - { url = "https://files.pythonhosted.org/packages/28/09/55f715ddbf95a054b764b547f617e22f1d5e45d83905660e9a088078fe67/PyYAML-6.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f003ed9ad21d6a4713f0a9b5a7a0a79e08dd0f221aff4525a2be4c346ee60aab", size = 167530 }, - { url = "https://files.pythonhosted.org/packages/5e/94/7d5ee059dfb92ca9e62f4057dcdec9ac08a9e42679644854dc01177f8145/PyYAML-6.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:42f8152b8dbc4fe7d96729ec2b99c7097d656dc1213a3229ca5383f973a5ed6d", size = 732244 }, - { url = "https://files.pythonhosted.org/packages/06/92/e0224aa6ebf9dc54a06a4609da37da40bb08d126f5535d81bff6b417b2ae/PyYAML-6.0.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:062582fca9fabdd2c8b54a3ef1c978d786e0f6b3a1510e0ac93ef59e0ddae2bc", size = 752871 }, - { url = "https://files.pythonhosted.org/packages/7b/5e/efd033ab7199a0b2044dab3b9f7a4f6670e6a52c089de572e928d2873b06/PyYAML-6.0.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d2b04aac4d386b172d5b9692e2d2da8de7bfb6c387fa4f801fbf6fb2e6ba4673", size = 757729 }, - { url = "https://files.pythonhosted.org/packages/03/5c/c4671451b2f1d76ebe352c0945d4cd13500adb5d05f5a51ee296d80152f7/PyYAML-6.0.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e7d73685e87afe9f3b36c799222440d6cf362062f78be1013661b00c5c6f678b", size = 748528 }, - { url = "https://files.pythonhosted.org/packages/73/9c/766e78d1efc0d1fca637a6b62cea1b4510a7fb93617eb805223294fef681/PyYAML-6.0.1-cp311-cp311-win32.whl", hash = "sha256:1635fd110e8d85d55237ab316b5b011de701ea0f29d07611174a1b42f1444741", size = 130286 }, - { url = "https://files.pythonhosted.org/packages/b3/34/65bb4b2d7908044963ebf614fe0fdb080773fc7030d7e39c8d3eddcd4257/PyYAML-6.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:bf07ee2fef7014951eeb99f56f39c9bb4af143d8aa3c21b1677805985307da34", size = 144699 }, - { url = "https://files.pythonhosted.org/packages/bc/06/1b305bf6aa704343be85444c9d011f626c763abb40c0edc1cad13bfd7f86/PyYAML-6.0.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:855fb52b0dc35af121542a76b9a84f8d1cd886ea97c84703eaa6d88e37a2ad28", size = 178692 }, - { url = "https://files.pythonhosted.org/packages/84/02/404de95ced348b73dd84f70e15a41843d817ff8c1744516bf78358f2ffd2/PyYAML-6.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:40df9b996c2b73138957fe23a16a4f0ba614f4c0efce1e9406a184b6d07fa3a9", size = 165622 }, - { url = "https://files.pythonhosted.org/packages/c7/4c/4a2908632fc980da6d918b9de9c1d9d7d7e70b2672b1ad5166ed27841ef7/PyYAML-6.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a08c6f0fe150303c1c6b71ebcd7213c2858041a7e01975da3a99aed1e7a378ef", size = 696937 }, - { url = "https://files.pythonhosted.org/packages/b4/33/720548182ffa8344418126017aa1d4ab4aeec9a2275f04ce3f3573d8ace8/PyYAML-6.0.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6c22bec3fbe2524cde73d7ada88f6566758a8f7227bfbf93a408a9d86bcc12a0", size = 724969 }, - { url = "https://files.pythonhosted.org/packages/4f/78/77b40157b6cb5f2d3d31a3d9b2efd1ba3505371f76730d267e8b32cf4b7f/PyYAML-6.0.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8d4e9c88387b0f5c7d5f281e55304de64cf7f9c0021a3525bd3b1c542da3b0e4", size = 712604 }, - { url = "https://files.pythonhosted.org/packages/2e/97/3e0e089ee85e840f4b15bfa00e4e63d84a3691ababbfea92d6f820ea6f21/PyYAML-6.0.1-cp312-cp312-win32.whl", hash = "sha256:d483d2cdf104e7c9fa60c544d92981f12ad66a457afae824d146093b8c294c54", size = 126098 }, - { url = "https://files.pythonhosted.org/packages/2b/9f/fbade56564ad486809c27b322d0f7e6a89c01f6b4fe208402e90d4443a99/PyYAML-6.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:0d3304d8c0adc42be59c5f8a4d9e3d7379e6955ad754aa9d6ab7a398b59dd1df", size = 138675 }, -] - -[[distribution]] +version = "6.0.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/54/ed/79a089b6be93607fa5cdaedf301d7dfb23af5f25c398d5ead2525b063e17/pyyaml-6.0.2.tar.gz", hash = "sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e", size = 130631 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/f8/aa/7af4e81f7acba21a4c6be026da38fd2b872ca46226673c89a758ebdc4fd2/PyYAML-6.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774", size = 184612 }, + { url = "https://files.pythonhosted.org/packages/8b/62/b9faa998fd185f65c1371643678e4d58254add437edb764a08c5a98fb986/PyYAML-6.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee", size = 172040 }, + { url = "https://files.pythonhosted.org/packages/ad/0c/c804f5f922a9a6563bab712d8dcc70251e8af811fce4524d57c2c0fd49a4/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c", size = 736829 }, + { url = "https://files.pythonhosted.org/packages/51/16/6af8d6a6b210c8e54f1406a6b9481febf9c64a3109c541567e35a49aa2e7/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317", size = 764167 }, + { url = "https://files.pythonhosted.org/packages/75/e4/2c27590dfc9992f73aabbeb9241ae20220bd9452df27483b6e56d3975cc5/PyYAML-6.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85", size = 762952 }, + { url = "https://files.pythonhosted.org/packages/9b/97/ecc1abf4a823f5ac61941a9c00fe501b02ac3ab0e373c3857f7d4b83e2b6/PyYAML-6.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4", size = 735301 }, + { url = "https://files.pythonhosted.org/packages/45/73/0f49dacd6e82c9430e46f4a027baa4ca205e8b0a9dce1397f44edc23559d/PyYAML-6.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e", size = 756638 }, + { url = "https://files.pythonhosted.org/packages/22/5f/956f0f9fc65223a58fbc14459bf34b4cc48dec52e00535c79b8db361aabd/PyYAML-6.0.2-cp311-cp311-win32.whl", hash = "sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5", size = 143850 }, + { url = "https://files.pythonhosted.org/packages/ed/23/8da0bbe2ab9dcdd11f4f4557ccaf95c10b9811b13ecced089d43ce59c3c8/PyYAML-6.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44", size = 161980 }, + { url = "https://files.pythonhosted.org/packages/86/0c/c581167fc46d6d6d7ddcfb8c843a4de25bdd27e4466938109ca68492292c/PyYAML-6.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab", size = 183873 }, + { url = "https://files.pythonhosted.org/packages/a8/0c/38374f5bb272c051e2a69281d71cba6fdb983413e6758b84482905e29a5d/PyYAML-6.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725", size = 173302 }, + { url = "https://files.pythonhosted.org/packages/c3/93/9916574aa8c00aa06bbac729972eb1071d002b8e158bd0e83a3b9a20a1f7/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5", size = 739154 }, + { url = "https://files.pythonhosted.org/packages/95/0f/b8938f1cbd09739c6da569d172531567dbcc9789e0029aa070856f123984/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425", size = 766223 }, + { url = "https://files.pythonhosted.org/packages/b9/2b/614b4752f2e127db5cc206abc23a8c19678e92b23c3db30fc86ab731d3bd/PyYAML-6.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476", size = 767542 }, + { url = "https://files.pythonhosted.org/packages/d4/00/dd137d5bcc7efea1836d6264f049359861cf548469d18da90cd8216cf05f/PyYAML-6.0.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48", size = 731164 }, + { url = "https://files.pythonhosted.org/packages/c9/1f/4f998c900485e5c0ef43838363ba4a9723ac0ad73a9dc42068b12aaba4e4/PyYAML-6.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b", size = 756611 }, + { url = "https://files.pythonhosted.org/packages/df/d1/f5a275fdb252768b7a11ec63585bc38d0e87c9e05668a139fea92b80634c/PyYAML-6.0.2-cp312-cp312-win32.whl", hash = "sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4", size = 140591 }, + { url = "https://files.pythonhosted.org/packages/0c/e8/4f648c598b17c3d06e8753d7d13d57542b30d56e6c2dedf9c331ae56312e/PyYAML-6.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8", size = 156338 }, + { url = "https://files.pythonhosted.org/packages/ef/e3/3af305b830494fa85d95f6d95ef7fa73f2ee1cc8ef5b495c7c3269fb835f/PyYAML-6.0.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:efdca5630322a10774e8e98e1af481aad470dd62c3170801852d752aa7a783ba", size = 181309 }, + { url = "https://files.pythonhosted.org/packages/45/9f/3b1c20a0b7a3200524eb0076cc027a970d320bd3a6592873c85c92a08731/PyYAML-6.0.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:50187695423ffe49e2deacb8cd10510bc361faac997de9efef88badc3bb9e2d1", size = 171679 }, + { url = "https://files.pythonhosted.org/packages/7c/9a/337322f27005c33bcb656c655fa78325b730324c78620e8328ae28b64d0c/PyYAML-6.0.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ffe8360bab4910ef1b9e87fb812d8bc0a308b0d0eef8c8f44e0254ab3b07133", size = 733428 }, + { url = "https://files.pythonhosted.org/packages/a3/69/864fbe19e6c18ea3cc196cbe5d392175b4cf3d5d0ac1403ec3f2d237ebb5/PyYAML-6.0.2-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:17e311b6c678207928d649faa7cb0d7b4c26a0ba73d41e99c4fff6b6c3276484", size = 763361 }, + { url = "https://files.pythonhosted.org/packages/04/24/b7721e4845c2f162d26f50521b825fb061bc0a5afcf9a386840f23ea19fa/PyYAML-6.0.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:70b189594dbe54f75ab3a1acec5f1e3faa7e8cf2f1e08d9b561cb41b845f69d5", size = 759523 }, + { url = "https://files.pythonhosted.org/packages/2b/b2/e3234f59ba06559c6ff63c4e10baea10e5e7df868092bf9ab40e5b9c56b6/PyYAML-6.0.2-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:41e4e3953a79407c794916fa277a82531dd93aad34e29c2a514c2c0c5fe971cc", size = 726660 }, + { url = "https://files.pythonhosted.org/packages/fe/0f/25911a9f080464c59fab9027482f822b86bf0608957a5fcc6eaac85aa515/PyYAML-6.0.2-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:68ccc6023a3400877818152ad9a1033e3db8625d899c72eacb5a668902e4d652", size = 751597 }, + { url = "https://files.pythonhosted.org/packages/14/0d/e2c3b43bbce3cf6bd97c840b46088a3031085179e596d4929729d8d68270/PyYAML-6.0.2-cp313-cp313-win32.whl", hash = "sha256:bc2fa7c6b47d6bc618dd7fb02ef6fdedb1090ec036abab80d4681424b84c1183", size = 140527 }, + { url = "https://files.pythonhosted.org/packages/fa/de/02b54f42487e3d3c6efb3f89428677074ca7bf43aae402517bc7cca949f3/PyYAML-6.0.2-cp313-cp313-win_amd64.whl", hash = "sha256:8388ee1976c416731879ac16da0aff3f63b286ffdd57cdeb95f3f2e085687563", size = 156446 }, +] + +[[package]] name = "pyyaml-env-tag" version = "0.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyyaml", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "pyyaml" }, ] sdist = { url = "https://files.pythonhosted.org/packages/fb/8e/da1c6c58f751b70f8ceb1eb25bc25d524e8f14fe16edcce3f4e3ba08629c/pyyaml_env_tag-0.1.tar.gz", hash = "sha256:70092675bda14fdec33b31ba77e7543de9ddc88f2e5b99160396572d11525bdb", size = 5631 } wheels = [ { url = "https://files.pythonhosted.org/packages/5a/66/bbb1dd374f5c870f59c5bb1db0e18cbe7fa739415a24cbd95b2d1f5ae0c4/pyyaml_env_tag-0.1-py3-none-any.whl", hash = "sha256:af31106dec8a4d68c60207c1886031cbf839b68aa7abccdb19868200532c2069", size = 3911 }, ] -[[distribution]] +[[package]] name = "pyzmq" version = "26.1.0" source = { registry = "https://pypi.org/simple" } @@ -4861,53 +4968,53 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0f/05/8ed4522919cc2ba381b677c09538dcf14b3a70038459e1b4c32a0341e0bb/pyzmq-26.1.0-cp313-cp313t-musllinux_1_1_x86_64.whl", hash = "sha256:91d1a20bdaf3b25f3173ff44e54b1cfbc05f94c9e8133314eb2962a89e05d6e3", size = 1392308 }, ] -[[distribution]] +[[package]] name = "requests" version = "2.32.3" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "certifi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "charset-normalizer", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "idna", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "urllib3", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "certifi" }, + { name = "charset-normalizer" }, + { name = "idna" }, + { name = "urllib3" }, ] sdist = { url = "https://files.pythonhosted.org/packages/63/70/2bf7780ad2d390a8d301ad0b550f1581eadbd9a20f896afe06353c2a2913/requests-2.32.3.tar.gz", hash = "sha256:55365417734eb18255590a9ff9eb97e9e1da868d4ccd6402399eaf68af20a760", size = 131218 } wheels = [ { url = "https://files.pythonhosted.org/packages/f9/9b/335f9764261e915ed497fcdeb11df5dfd6f7bf257d4a6a2a686d80da4d54/requests-2.32.3-py3-none-any.whl", hash = "sha256:70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6", size = 64928 }, ] -[[distribution]] +[[package]] name = "rerun-sdk" -version = "0.17.0" +version = "0.18.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "attrs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pillow", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pyarrow", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "typing-extensions", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "attrs" }, + { name = "numpy" }, + { name = "pillow" }, + { name = "pyarrow" }, + { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/30/5f/ce02381b9d7e1e14f60c421c76dce12b7d823690181784780b30266017b1/rerun_sdk-0.17.0-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:abd34f746eada83b8bb0bc50007183151981d7ccf18306f3d42165819a3f6fcb", size = 33166544 }, - { url = "https://files.pythonhosted.org/packages/b7/c5/d47ba7b774bc563aa3c07ba500dd304ea24b31fe438e10ea9ad5e10ffe17/rerun_sdk-0.17.0-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:8b0a8a6feab3f8e679801d158216a71d88a81480021587719330f50d083c4d26", size = 32237860 }, - { url = "https://files.pythonhosted.org/packages/87/0a/b5fe1ffea700eeaa8d28817a92ad3cb4a7d56dc4af45de76ea412cfc5cd5/rerun_sdk-0.17.0-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:ad55807abafb01e527846742e087819aac8e103f1ec15aadc563a4038bb44e1d", size = 38608604 }, - { url = "https://files.pythonhosted.org/packages/d9/74/6c1ff0c8dbe6da09ceb5ea838a72382fa3131ef6bb9377a30003299743fa/rerun_sdk-0.17.0-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:9d41f1f475270b1e0d50ddb8cb62e0d828988f0c371ac8457af25c8be5aa1dc0", size = 38917319 }, - { url = "https://files.pythonhosted.org/packages/8c/28/92423fe9673b738c180fb5b6b8ea4203fe4b02c1d20b06b7fae79d11cc24/rerun_sdk-0.17.0-cp38-abi3-win_amd64.whl", hash = "sha256:34e5595a326cbdddfebdf00b08e877358c564fce74cc8c6d617fc89ef3a6aa70", size = 29490986 }, + { url = "https://files.pythonhosted.org/packages/12/05/639478e82e619554067e99f646af32df2b8f5c3a3e19c5e0899aa3fe7077/rerun_sdk-0.18.0-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:dc18de6f5e1a7b344d02d24a454bdcc10ce1099ce7151c2d93a044d76c6ce8f3", size = 32935334 }, + { url = "https://files.pythonhosted.org/packages/21/ec/8faf4150b84548bab9d58da24a2be5e7f79dfe9ba8a7af1ec0ea4e1a50ac/rerun_sdk-0.18.0-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:a7bb437636ad69ade2dbc06f837cb506fcffc192a0881f4a44e1a89681eba4b0", size = 32014149 }, + { url = "https://files.pythonhosted.org/packages/8a/a8/20708dcedce4e1ed15148a3d12052152854e3239c69cc276d0d0f3cf21e9/rerun_sdk-0.18.0-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:c17cb73de92be9c0bbd5d08e02bdec1defa86328dcb05f8154d5c3fa7e42fcc7", size = 38365605 }, + { url = "https://files.pythonhosted.org/packages/a3/95/f1133bcfa08f4c93c1ee2ee67c7e13f5b9cdb9b978e8a7607896272dbf91/rerun_sdk-0.18.0-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:db4f783c22b5ce61915394e5fa3ad3c4045bdb00f12984862cd0c4372bff89da", size = 38685748 }, + { url = "https://files.pythonhosted.org/packages/f9/41/8f80942f4a7166c871f3c20648debe87bf6f8a8884f36372f2cab5cb5f19/rerun_sdk-0.18.0-cp38-abi3-win_amd64.whl", hash = "sha256:4c4dde49fcb08eb34c51dfe8a12733f96102f44bd1dc89063b08d65de1a06cdb", size = 29437290 }, ] -[[distribution]] +[[package]] name = "ruamel-yaml" version = "0.18.6" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "ruamel-yaml-clib", marker = "python_version < '3.13' and platform_python_implementation == 'CPython'" }, + { name = "ruamel-yaml-clib", marker = "python_full_version < '3.13' and platform_python_implementation == 'CPython'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/29/81/4dfc17eb6ebb1aac314a3eb863c1325b907863a1b8b1382cdffcb6ac0ed9/ruamel.yaml-0.18.6.tar.gz", hash = "sha256:8b27e6a217e786c6fbe5634d8f3f11bc63e0f80f6a5890f28863d9c45aac311b", size = 143362 } wheels = [ { url = "https://files.pythonhosted.org/packages/73/67/8ece580cc363331d9a53055130f86b096bf16e38156e33b1d3014fffda6b/ruamel.yaml-0.18.6-py3-none-any.whl", hash = "sha256:57b53ba33def16c4f3d807c0ccbc00f8a6081827e81ba2491691b76882d0c636", size = 117761 }, ] -[[distribution]] +[[package]] name = "ruamel-yaml-clib" version = "0.2.8" source = { registry = "https://pypi.org/simple" } @@ -4931,7 +5038,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/10/d2/52a3d810d0b5b3720725c0504a27b3fced7b6f310fe928f7019d79387bc1/ruamel.yaml.clib-0.2.8-cp312-cp312-win_amd64.whl", hash = "sha256:1758ce7d8e1a29d23de54a16ae867abd370f01b5a69e1a3ba75223eaa3ca1a1b", size = 115305 }, ] -[[distribution]] +[[package]] name = "rubicon-objc" version = "0.4.9" source = { registry = "https://pypi.org/simple" } @@ -4940,37 +5047,37 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/0b/e3/f3d12557a4eed94dc88c780e0eac87f04d232d1a4f1beffc3fb0e50dc330/rubicon_objc-0.4.9-py3-none-any.whl", hash = "sha256:c351b3800cf74c8c23f7d534f008fd5de46c63818de7a44de96daffdb3ed8b8c", size = 63022 }, ] -[[distribution]] +[[package]] name = "ruff" -version = "0.5.6" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/f7/69/96766da2cdb5605e6a31ef2734aff0be17901cefb385b885c2ab88896d76/ruff-0.5.6.tar.gz", hash = "sha256:07c9e3c2a8e1fe377dd460371c3462671a728c981c3205a5217291422209f642", size = 2444466 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/85/54/af603686de0e9ba6c1798bd83d335e345e7c9ce4deed95a1071448bb6563/ruff-0.5.6-py3-none-linux_armv6l.whl", hash = "sha256:a0ef5930799a05522985b9cec8290b185952f3fcd86c1772c3bdbd732667fdcd", size = 9543715 }, - { url = "https://files.pythonhosted.org/packages/81/86/b22d250e1be2dcd11c749817d0cfe8be37efce6e6862c92ea037bedf6df9/ruff-0.5.6-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:b652dc14f6ef5d1552821e006f747802cc32d98d5509349e168f6bf0ee9f8f42", size = 8662814 }, - { url = "https://files.pythonhosted.org/packages/d2/e2/f97c58797fac1c7dd8226becfed55056fa7bbfb6d9c2e93900f2a27b540e/ruff-0.5.6-py3-none-macosx_11_0_arm64.whl", hash = "sha256:80521b88d26a45e871f31e4b88938fd87db7011bb961d8afd2664982dfc3641a", size = 8230427 }, - { url = "https://files.pythonhosted.org/packages/24/70/9f00cf1e2b50476751808ac6ebbfaa6dab3abab5514058f6bbca28a790bc/ruff-0.5.6-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d9bc8f328a9f1309ae80e4d392836e7dbc77303b38ed4a7112699e63d3b066ab", size = 9976713 }, - { url = "https://files.pythonhosted.org/packages/9b/02/309b171d867d819b7c76c46489597341ce85d70fefa05102a95130440005/ruff-0.5.6-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:4d394940f61f7720ad371ddedf14722ee1d6250fd8d020f5ea5a86e7be217daf", size = 9345335 }, - { url = "https://files.pythonhosted.org/packages/37/42/74b84b97815a0b940f1438ff554ead1405d2556ff8e2da58d3c3068a2093/ruff-0.5.6-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:111a99cdb02f69ddb2571e2756e017a1496c2c3a2aeefe7b988ddab38b416d36", size = 10140380 }, - { url = "https://files.pythonhosted.org/packages/47/0c/705b979fe814498dfc3977bcdbf8c47059d2ed37b1c2128f1b77612eea82/ruff-0.5.6-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:e395daba77a79f6dc0d07311f94cc0560375ca20c06f354c7c99af3bf4560c5d", size = 10853490 }, - { url = "https://files.pythonhosted.org/packages/56/f1/400cc9a533fadba676783a2116526d1c26063d3228105bc75fa1c32a092b/ruff-0.5.6-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c476acb43c3c51e3c614a2e878ee1589655fa02dab19fe2db0423a06d6a5b1b6", size = 10425500 }, - { url = "https://files.pythonhosted.org/packages/f3/cd/f2cf6bc23a4293e3f8c365138f7279eea9179d1c4d3e09546d64daea40da/ruff-0.5.6-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e2ff8003f5252fd68425fd53d27c1f08b201d7ed714bb31a55c9ac1d4c13e2eb", size = 11407463 }, - { url = "https://files.pythonhosted.org/packages/f8/cc/227428f39f8834d281b6d18f84f53e08a840ed63dec259e5e5e502284cec/ruff-0.5.6-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c94e084ba3eaa80c2172918c2ca2eb2230c3f15925f4ed8b6297260c6ef179ad", size = 10160402 }, - { url = "https://files.pythonhosted.org/packages/f3/61/218890d960ca146d3822e981a34834995081f3b741b82ca2585fd5ebc521/ruff-0.5.6-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:1f77c1c3aa0669fb230b06fb24ffa3e879391a3ba3f15e3d633a752da5a3e670", size = 9971344 }, - { url = "https://files.pythonhosted.org/packages/f1/20/bd444745ff7b51e497332ecf3f550bb62871dd24d61960997049fdbed268/ruff-0.5.6-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:f908148c93c02873210a52cad75a6eda856b2cbb72250370ce3afef6fb99b1ed", size = 9417963 }, - { url = "https://files.pythonhosted.org/packages/30/03/69b6d3735f284d93324ca31e36316574501130393f1a8e328a74775f4fb5/ruff-0.5.6-py3-none-musllinux_1_2_i686.whl", hash = "sha256:563a7ae61ad284187d3071d9041c08019975693ff655438d8d4be26e492760bd", size = 9769870 }, - { url = "https://files.pythonhosted.org/packages/7f/19/1c86dc40abef457124bb4abf90c68688eb2c7f9944903240c3b93d511360/ruff-0.5.6-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:94fe60869bfbf0521e04fd62b74cbca21cbc5beb67cbb75ab33fe8c174f54414", size = 10229991 }, - { url = "https://files.pythonhosted.org/packages/65/a7/60a19f3cfccdea5815bc31971f523f5b2ecd08162b05d1a0d5b8c37dff59/ruff-0.5.6-py3-none-win32.whl", hash = "sha256:e6a584c1de6f8591c2570e171cc7ce482bb983d49c70ddf014393cd39e9dfaed", size = 7789030 }, - { url = "https://files.pythonhosted.org/packages/27/c6/b51987072bba4a56537b6fc7036d9bf0694a9de6cceddaa0761475658632/ruff-0.5.6-py3-none-win_amd64.whl", hash = "sha256:d7fe7dccb1a89dc66785d7aa0ac283b2269712d8ed19c63af908fdccca5ccc1a", size = 8690520 }, - { url = "https://files.pythonhosted.org/packages/c0/b1/712801cf487fd78554029b02f980e24531f5994e2bf79b7ac55c1659dd52/ruff-0.5.6-py3-none-win_arm64.whl", hash = "sha256:57c6c0dd997b31b536bff49b9eee5ed3194d60605a4427f735eeb1f9c1b8d264", size = 8101938 }, -] - -[[distribution]] +version = "0.5.7" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/bf/2b/69e5e412f9d390adbdbcbf4f64d6914fa61b44b08839a6584655014fc524/ruff-0.5.7.tar.gz", hash = "sha256:8dfc0a458797f5d9fb622dd0efc52d796f23f0a1493a9527f4e49a550ae9a7e5", size = 2449817 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6b/eb/06e06aaf96af30a68e83b357b037008c54a2ddcbad4f989535007c700394/ruff-0.5.7-py3-none-linux_armv6l.whl", hash = "sha256:548992d342fc404ee2e15a242cdbea4f8e39a52f2e7752d0e4cbe88d2d2f416a", size = 9570571 }, + { url = "https://files.pythonhosted.org/packages/a4/10/1be32aeaab8728f78f673e7a47dd813222364479b2d6573dbcf0085e83ea/ruff-0.5.7-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:00cc8872331055ee017c4f1071a8a31ca0809ccc0657da1d154a1d2abac5c0be", size = 8685138 }, + { url = "https://files.pythonhosted.org/packages/3d/1d/c218ce83beb4394ba04d05e9aa2ae6ce9fba8405688fe878b0fdb40ce855/ruff-0.5.7-py3-none-macosx_11_0_arm64.whl", hash = "sha256:eaf3d86a1fdac1aec8a3417a63587d93f906c678bb9ed0b796da7b59c1114a1e", size = 8266785 }, + { url = "https://files.pythonhosted.org/packages/26/79/7f49509bd844476235b40425756def366b227a9714191c91f02fb2178635/ruff-0.5.7-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a01c34400097b06cf8a6e61b35d6d456d5bd1ae6961542de18ec81eaf33b4cb8", size = 9983964 }, + { url = "https://files.pythonhosted.org/packages/bf/b1/939836b70bf9fcd5e5cd3ea67fdb8abb9eac7631351d32f26544034a35e4/ruff-0.5.7-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:fcc8054f1a717e2213500edaddcf1dbb0abad40d98e1bd9d0ad364f75c763eea", size = 9359490 }, + { url = "https://files.pythonhosted.org/packages/32/7d/b3db19207de105daad0c8b704b2c6f2a011f9c07017bd58d8d6e7b8eba19/ruff-0.5.7-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7f70284e73f36558ef51602254451e50dd6cc479f8b6f8413a95fcb5db4a55fc", size = 10170833 }, + { url = "https://files.pythonhosted.org/packages/a2/45/eae9da55f3357a1ac04220230b8b07800bf516e6dd7e1ad20a2ff3b03b1b/ruff-0.5.7-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:a78ad870ae3c460394fc95437d43deb5c04b5c29297815a2a1de028903f19692", size = 10896360 }, + { url = "https://files.pythonhosted.org/packages/99/67/4388b36d145675f4c51ebec561fcd4298a0e2550c81e629116f83ce45a39/ruff-0.5.7-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9ccd078c66a8e419475174bfe60a69adb36ce04f8d4e91b006f1329d5cd44bcf", size = 10477094 }, + { url = "https://files.pythonhosted.org/packages/e1/9c/f5e6ed1751dc187a4ecf19a4970dd30a521c0ee66b7941c16e292a4043fb/ruff-0.5.7-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7e31c9bad4ebf8fdb77b59cae75814440731060a09a0e0077d559a556453acbb", size = 11480896 }, + { url = "https://files.pythonhosted.org/packages/c8/3b/2b683be597bbd02046678fc3fc1c199c641512b20212073b58f173822bb3/ruff-0.5.7-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8d796327eed8e168164346b769dd9a27a70e0298d667b4ecee6877ce8095ec8e", size = 10179702 }, + { url = "https://files.pythonhosted.org/packages/f1/38/c2d94054dc4b3d1ea4c2ba3439b2a7095f08d1c8184bc41e6abe2a688be7/ruff-0.5.7-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:4a09ea2c3f7778cc635e7f6edf57d566a8ee8f485f3c4454db7771efb692c499", size = 9982855 }, + { url = "https://files.pythonhosted.org/packages/7d/e7/1433db2da505ffa8912dcf5b28a8743012ee780cbc20ad0bf114787385d9/ruff-0.5.7-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:a36d8dcf55b3a3bc353270d544fb170d75d2dff41eba5df57b4e0b67a95bb64e", size = 9433156 }, + { url = "https://files.pythonhosted.org/packages/e0/36/4fa43250e67741edeea3d366f59a1dc993d4d89ad493a36cbaa9889895f2/ruff-0.5.7-py3-none-musllinux_1_2_i686.whl", hash = "sha256:9369c218f789eefbd1b8d82a8cf25017b523ac47d96b2f531eba73770971c9e5", size = 9782971 }, + { url = "https://files.pythonhosted.org/packages/80/0e/8c276103d518e5cf9202f70630aaa494abf6fc71c04d87c08b6d3cd07a4b/ruff-0.5.7-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:b88ca3db7eb377eb24fb7c82840546fb7acef75af4a74bd36e9ceb37a890257e", size = 10247775 }, + { url = "https://files.pythonhosted.org/packages/cb/b9/673096d61276f39291b729dddde23c831a5833d98048349835782688a0ec/ruff-0.5.7-py3-none-win32.whl", hash = "sha256:33d61fc0e902198a3e55719f4be6b375b28f860b09c281e4bdbf783c0566576a", size = 7841772 }, + { url = "https://files.pythonhosted.org/packages/67/1c/4520c98bfc06b9c73cd1457686d4d3935d40046b1ddea08403e5a6deff51/ruff-0.5.7-py3-none-win_amd64.whl", hash = "sha256:083bbcbe6fadb93cd86709037acc510f86eed5a314203079df174c40bbbca6b3", size = 8699779 }, + { url = "https://files.pythonhosted.org/packages/38/23/b3763a237d2523d40a31fe2d1a301191fe392dd48d3014977d079cf8c0bd/ruff-0.5.7-py3-none-win_arm64.whl", hash = "sha256:2dca26154ff9571995107221d0aeaad0e75a77b5a682d6236cf89a58c70b76f4", size = 8091891 }, +] + +[[package]] name = "scipy" version = "1.14.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4e/e5/0230da034a2e1b1feb32621d7cd57c59484091d6dccc9e6b855b0d309fc9/scipy-1.14.0.tar.gz", hash = "sha256:b5923f48cb840380f9854339176ef21763118a7300a88203ccd0bdd26e58527b", size = 58618870 } wheels = [ @@ -4992,7 +5099,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3f/72/305686527c68f33f1dd3ebdd28f53340d372b2f9e44dccaf6f92e17739d3/scipy-1.14.0-cp312-cp312-win_amd64.whl", hash = "sha256:4c4161597c75043f7154238ef419c29a64ac4a7c889d588ea77690ac4d0d9b20", size = 44475988 }, ] -[[distribution]] +[[package]] name = "scons" version = "4.8.0" source = { registry = "https://pypi.org/simple" } @@ -5001,34 +5108,34 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7b/01/4ea08ba8414db39e597939ff82d587082674f616f78e3dc505dae4b6a176/SCons-4.8.0-py3-none-any.whl", hash = "sha256:760fbfd05e459113e9a1362ab2b00e12ea4195607e820a127d30e6275c8436a1", size = 4122772 }, ] -[[distribution]] +[[package]] name = "seaborn" version = "0.13.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "matplotlib", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "pandas", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "matplotlib" }, + { name = "numpy" }, + { name = "pandas" }, ] sdist = { url = "https://files.pythonhosted.org/packages/86/59/a451d7420a77ab0b98f7affa3a1d78a313d2f7281a57afb1a34bae8ab412/seaborn-0.13.2.tar.gz", hash = "sha256:93e60a40988f4d65e9f4885df477e2fdaff6b73a9ded434c1ab356dd57eefff7", size = 1457696 } wheels = [ { url = "https://files.pythonhosted.org/packages/83/11/00d3c3dfc25ad54e731d91449895a79e4bf2384dc3ac01809010ba88f6d5/seaborn-0.13.2-py3-none-any.whl", hash = "sha256:636f8336facf092165e27924f223d3c62ca560b1f2bb5dff7ab7fad265361987", size = 294914 }, ] -[[distribution]] +[[package]] name = "sentry-sdk" version = "2.12.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "certifi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "urllib3", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "certifi" }, + { name = "urllib3" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2e/39/eb97e463e372b38d0b9c7ae705822d1df717940c04cb6d998ae15bf3eb02/sentry_sdk-2.12.0.tar.gz", hash = "sha256:8763840497b817d44c49b3fe3f5f7388d083f2337ffedf008b2cdb63b5c86dc6", size = 274179 } wheels = [ { url = "https://files.pythonhosted.org/packages/71/29/744921222eb1bfef7a7e16e71fc122f518b315fc57624828b90028dfa02e/sentry_sdk-2.12.0-py2.py3-none-any.whl", hash = "sha256:7a8d5163d2ba5c5f4464628c6b68f85e86972f7c636acc78aed45c61b98b7a5e", size = 301807 }, ] -[[distribution]] +[[package]] name = "setproctitle" version = "1.3.3" source = { registry = "https://pypi.org/simple" } @@ -5060,7 +5167,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/90/e8/ece468e93e99d3b2826e9649f6d03e80f071d451e20c742f201f77d1bea1/setproctitle-1.3.3-cp312-cp312-win_amd64.whl", hash = "sha256:f38d48abc121263f3b62943f84cbaede05749047e428409c2c199664feb6abc7", size = 11809 }, ] -[[distribution]] +[[package]] name = "setuptools" version = "72.1.0" source = { registry = "https://pypi.org/simple" } @@ -5069,12 +5176,12 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e1/58/e0ef3b9974a04ce9cde2a7a33881ddcb2d68450803745804545cdd8d258f/setuptools-72.1.0-py3-none-any.whl", hash = "sha256:5a03e1860cf56bb6ef48ce186b0e557fdba433237481a9a625176c2831be15d1", size = 2337965 }, ] -[[distribution]] +[[package]] name = "shapely" version = "2.0.5" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "numpy", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ad/99/c47247f4d688bbb5346df5ff1de5d9792b6d95cbbb2fd7b71f45901c1878/shapely-2.0.5.tar.gz", hash = "sha256:bff2366bc786bfa6cb353d6b47d0443c570c32776612e527ee47b6df63fcfe32", size = 282188 } wheels = [ @@ -5092,7 +5199,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d4/c3/e98e3eb9f06def32b8e2454ab718cafb99149f023dff023e257125132d6e/shapely-2.0.5-cp312-cp312-win_amd64.whl", hash = "sha256:30e8737983c9d954cd17feb49eb169f02f1da49e24e5171122cf2c2b62d65c95", size = 1442365 }, ] -[[distribution]] +[[package]] name = "siphash24" version = "1.6" source = { registry = "https://pypi.org/simple" } @@ -5112,7 +5219,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ef/de/6ebd0f96184f8479e8348dcba93a9f14ff54ac3c6a68866cc77c334d7bdf/siphash24-1.6-cp312-cp312-win_amd64.whl", hash = "sha256:226af78af3b992c953cc4808f2c6a4bba320e91e6c89b34aa2492064fa417ae8", size = 81096 }, ] -[[distribution]] +[[package]] name = "six" version = "1.16.0" source = { registry = "https://pypi.org/simple" } @@ -5121,7 +5228,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d9/5a/e7c31adbe875f2abbb91bd84cf2dc52d792b5a01506781dbcf25c91daf11/six-1.16.0-py2.py3-none-any.whl", hash = "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254", size = 11053 }, ] -[[distribution]] +[[package]] name = "smbus2" version = "0.4.3" source = { registry = "https://pypi.org/simple" } @@ -5130,7 +5237,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/d6/5b/3ada173f07b4ec9bfa03b779e59ecada48eb7cb1a29f51cfce70edce7f3f/smbus2-0.4.3-py2.py3-none-any.whl", hash = "sha256:a2fc29cfda4081ead2ed61ef2c4fc041d71dd40a8d917e85216f44786fca2d1d", size = 11553 }, ] -[[distribution]] +[[package]] name = "sortedcontainers" version = "2.4.0" source = { registry = "https://pypi.org/simple" } @@ -5139,40 +5246,40 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/32/46/9cb0e58b2deb7f82b84065f37f3bffeb12413f947f9388e4cac22c4621ce/sortedcontainers-2.4.0-py2.py3-none-any.whl", hash = "sha256:a163dcaede0f1c021485e957a39245190e74249897e2ae4b2aa38595db237ee0", size = 29575 }, ] -[[distribution]] +[[package]] name = "sounddevice" -version = "0.4.7" +version = "0.5.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cffi", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "cffi" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0d/88/5832219fa90595932d5f6d1b5125bfd8a55e95b19ad866e265c9bbb7cde4/sounddevice-0.4.7.tar.gz", hash = "sha256:69b386818d50a2d518607d4b973442e8d524760c7cd6c8b8be03d8c98fc4bce7", size = 52244 } +sdist = { url = "https://files.pythonhosted.org/packages/87/92/62d87d7b53a4e1041f0d9e049e225fce3c7bc266c0162c023feb245b999d/sounddevice-0.5.0.tar.gz", hash = "sha256:0de95277654b3d403d9c15ded3c6cedf307e9b27cc9ce7bd995a2891d0c955af", size = 52564 } wheels = [ - { url = "https://files.pythonhosted.org/packages/46/ea/e9196f01ec3c5ad537e1bb83fe08da3bacfbdfee8a872c461e491f489801/sounddevice-0.4.7-py3-none-any.whl", hash = "sha256:1c3f18bfa4d9a257f5715f2ab83f2c0eb412a09f3e6a9fa73720886ca88f6bc7", size = 32092 }, - { url = "https://files.pythonhosted.org/packages/1c/9c/d8de668a462b7a326d9f697dfa2adb6fbde07cc468cc7cdcf51cbe975d56/sounddevice-0.4.7-py3-none-macosx_10_6_x86_64.macosx_10_6_universal2.whl", hash = "sha256:d6ddfd341ad7412b14ca001f2c4dbf5fa2503bdc9eb15ad2c3105f6c260b698a", size = 108360 }, - { url = "https://files.pythonhosted.org/packages/96/7f/620dda64a6e7fbdab11ca9065ae72668c78dc331058f51175a62a8fede12/sounddevice-0.4.7-py3-none-win32.whl", hash = "sha256:1ec1df094c468a210113aa22c4f390d5b4d9c7a73e41a6cb6ecfec83db59b380", size = 197641 }, - { url = "https://files.pythonhosted.org/packages/d4/09/bfdd393f1bb1b90b4a6849b84972b7059c95e36818cc489922228d58cc63/sounddevice-0.4.7-py3-none-win_amd64.whl", hash = "sha256:0c8b3543da1496f282b66a7bc54b755577ba638b1af06c146d4ac7f39d86b548", size = 200096 }, + { url = "https://files.pythonhosted.org/packages/e6/3c/241480772b55a39d4c07f2d88cf43e0a2955cc662f369c33dfb4fb79e9fa/sounddevice-0.5.0-py3-none-any.whl", hash = "sha256:8a734043ab1f751cb20f6f25d8f07408a1aadf2eeca923061849d38bb59f9e3d", size = 32107 }, + { url = "https://files.pythonhosted.org/packages/61/10/10f05bbe463424467bb24e4804130fb854d7cc0bc7aa7c040867f21cc997/sounddevice-0.5.0-py3-none-macosx_10_6_x86_64.macosx_10_6_universal2.whl", hash = "sha256:73eb7cb1e8ab1e1ba09c228239e9d0b160006de380921687e44610ad9a19ac32", size = 107746 }, + { url = "https://files.pythonhosted.org/packages/73/4c/783f44af582a5e6cdecbc14e154ab0775c9e645a9567869facd172ecd582/sounddevice-0.5.0-py3-none-win32.whl", hash = "sha256:919de43040e8737258370ddf929a9cd1a3d6c493ca173bab70a3c7cb15c71e97", size = 167621 }, + { url = "https://files.pythonhosted.org/packages/bf/2a/58fa1704b5cf8041564337674790426d39d630e7407e54e17a1212332959/sounddevice-0.5.0-py3-none-win_amd64.whl", hash = "sha256:f28b7ef16f293d7b048a614dd087dfe39c3e313d94a50539bb52022b7ef27ece", size = 189785 }, ] -[[distribution]] +[[package]] name = "spidev" version = "3.6" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/c7/d9/401c0a7be089e02826cf2c201f489876b601f15be100fe391ef9c2faed83/spidev-3.6.tar.gz", hash = "sha256:14dbc37594a4aaef85403ab617985d3c3ef464d62bc9b769ef552db53701115b", size = 11917 } -[[distribution]] +[[package]] name = "sympy" -version = "1.13.1" +version = "1.13.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "mpmath", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "mpmath" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ca/99/5a5b6f19ff9f083671ddf7b9632028436167cd3d33e11015754e41b249a4/sympy-1.13.1.tar.gz", hash = "sha256:9cebf7e04ff162015ce31c9c6c9144daa34a93bd082f54fd8f12deca4f47515f", size = 7533040 } +sdist = { url = "https://files.pythonhosted.org/packages/94/15/4a041424c7187f41cce678f5a02189b244e9aac61a18b45cd415a3a470f3/sympy-1.13.2.tar.gz", hash = "sha256:401449d84d07be9d0c7a46a64bd54fe097667d5e7181bfe67ec777be9e01cb13", size = 7532926 } wheels = [ - { url = "https://files.pythonhosted.org/packages/b2/fe/81695a1aa331a842b582453b605175f419fe8540355886031328089d840a/sympy-1.13.1-py3-none-any.whl", hash = "sha256:db36cdc64bf61b9b24578b6f7bab1ecdd2452cf008f34faa33776680c26d66f8", size = 6189177 }, + { url = "https://files.pythonhosted.org/packages/c1/f9/6845bf8fca0eaf847da21c5d5bc6cd92797364662824a11d3f836423a1a5/sympy-1.13.2-py3-none-any.whl", hash = "sha256:c51d75517712f1aed280d4ce58506a4a88d635d6b5dd48b39102a7ae1f3fcfe9", size = 6189289 }, ] -[[distribution]] +[[package]] name = "tabulate" version = "0.9.0" source = { registry = "https://pypi.org/simple" } @@ -5181,7 +5288,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/40/44/4a5f08c96eb108af5cb50b41f76142f0afa346dfa99d5296fe7202a11854/tabulate-0.9.0-py3-none-any.whl", hash = "sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f", size = 35252 }, ] -[[distribution]] +[[package]] name = "tomli" version = "2.0.1" source = { registry = "https://pypi.org/simple" } @@ -5190,7 +5297,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/97/75/10a9ebee3fd790d20926a90a2547f0bf78f371b2f13aa822c759680ca7b9/tomli-2.0.1-py3-none-any.whl", hash = "sha256:939de3e7a6161af0c887ef91b7d41a53e7c5a1ca976325f429cb46ea9bc30ecc", size = 12757 }, ] -[[distribution]] +[[package]] name = "tqdm" version = "4.66.5" source = { registry = "https://pypi.org/simple" } @@ -5202,19 +5309,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/48/5d/acf5905c36149bbaec41ccf7f2b68814647347b72075ac0b1fe3022fdc73/tqdm-4.66.5-py3-none-any.whl", hash = "sha256:90279a3770753eafc9194a0364852159802111925aa30eb3f9d85b0e805ac7cd", size = 78351 }, ] -[[distribution]] +[[package]] name = "types-requests" version = "2.32.0.20240712" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "urllib3", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "urllib3" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5e/9e/7663eb27c33568b8fc20ccdaf2a1ce53a9530c42a7cceb9f552a6ff4a1d8/types-requests-2.32.0.20240712.tar.gz", hash = "sha256:90c079ff05e549f6bf50e02e910210b98b8ff1ebdd18e19c873cd237737c1358", size = 17896 } wheels = [ { url = "https://files.pythonhosted.org/packages/30/4d/cbed87a6912fbd9259ce23a5d4aa1de9816edf75eec6ed9a757c00906c8e/types_requests-2.32.0.20240712-py3-none-any.whl", hash = "sha256:f754283e152c752e46e70942fa2a146b5bc70393522257bb85bd1ef7e019dcc3", size = 15816 }, ] -[[distribution]] +[[package]] name = "types-tabulate" version = "0.9.0.20240106" source = { registry = "https://pypi.org/simple" } @@ -5223,7 +5330,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f0/17/d53c0bb370100313df6800e9096bdfc27b32b8e4a9390bfb35bc4b17db78/types_tabulate-0.9.0.20240106-py3-none-any.whl", hash = "sha256:0378b7b6fe0ccb4986299496d027a6d4c218298ecad67199bbd0e2d7e9d335a1", size = 3350 }, ] -[[distribution]] +[[package]] name = "typing-extensions" version = "4.12.2" source = { registry = "https://pypi.org/simple" } @@ -5232,7 +5339,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/26/9f/ad63fc0248c5379346306f8668cda6e2e2e9c95e01216d2b8ffd9ff037d0/typing_extensions-4.12.2-py3-none-any.whl", hash = "sha256:04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d", size = 37438 }, ] -[[distribution]] +[[package]] name = "tzdata" version = "2024.1" source = { registry = "https://pypi.org/simple" } @@ -5241,7 +5348,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/65/58/f9c9e6be752e9fcb8b6a0ee9fb87e6e7a1f6bcab2cdc73f02bb7ba91ada0/tzdata-2024.1-py2.py3-none-any.whl", hash = "sha256:9068bc196136463f5245e51efda838afa15aaeca9903f49050dfa2679db4d252", size = 345370 }, ] -[[distribution]] +[[package]] name = "urllib3" version = "2.2.2" source = { registry = "https://pypi.org/simple" } @@ -5250,31 +5357,34 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ca/1c/89ffc63a9605b583d5df2be791a27bc1a42b7c32bab68d3c8f2f73a98cd4/urllib3-2.2.2-py3-none-any.whl", hash = "sha256:a448b2f64d686155468037e1ace9f2d2199776e17f0a46610480d311f73e3472", size = 121444 }, ] -[[distribution]] +[[package]] name = "watchdog" -version = "4.0.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1b/f9/b01e4632aed9a6ecc2b3e501feffd3af5aa0eb4e3b0283fc9525bf503c38/watchdog-4.0.1.tar.gz", hash = "sha256:eebaacf674fa25511e8867028d281e602ee6500045b57f43b08778082f7f8b44", size = 126583 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1c/bc/a1ce8b77eede5a2f4fbcdc923079eb85b7c6e0f5e366ad06661b4dd807e1/watchdog-4.0.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:17e32f147d8bf9657e0922c0940bcde863b894cd871dbb694beb6704cfbd2fb5", size = 101627 }, - { url = "https://files.pythonhosted.org/packages/c2/84/9c66fb603bb683fe559ceeba8f3d5dbea3293b631b2eba319d7d47a2d7fb/watchdog-4.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:03e70d2df2258fb6cb0e95bbdbe06c16e608af94a3ffbd2b90c3f1e83eb10767", size = 92464 }, - { url = "https://files.pythonhosted.org/packages/5a/a5/72b9557e77ac3e6c41816fb16f643069b17cf21f745d26e2931cb1bf136c/watchdog-4.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:123587af84260c991dc5f62a6e7ef3d1c57dfddc99faacee508c71d287248459", size = 92953 }, - { url = "https://files.pythonhosted.org/packages/f3/d1/85c1f5841190ee1e39f4a8a01df6eb13b44bd366060fc735505a38613484/watchdog-4.0.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:093b23e6906a8b97051191a4a0c73a77ecc958121d42346274c6af6520dec175", size = 101708 }, - { url = "https://files.pythonhosted.org/packages/a9/eb/8d1f9150dd5e86082913ab15d4fd4bea436186845be1b1752efd19b020d1/watchdog-4.0.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:611be3904f9843f0529c35a3ff3fd617449463cb4b73b1633950b3d97fa4bfb7", size = 92508 }, - { url = "https://files.pythonhosted.org/packages/52/67/62eea67ef31214ea4867b97351ea4f6b3a52dd1c4c93360ff8ad6e4ad72f/watchdog-4.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:62c613ad689ddcb11707f030e722fa929f322ef7e4f18f5335d2b73c61a85c28", size = 92977 }, - { url = "https://files.pythonhosted.org/packages/3a/36/28ce38b960f2bf1e1be573d85e8127c9ac66b4de63a7bef3f61b3f77ce57/watchdog-4.0.1-py3-none-manylinux2014_aarch64.whl", hash = "sha256:dddba7ca1c807045323b6af4ff80f5ddc4d654c8bce8317dde1bd96b128ed253", size = 83011 }, - { url = "https://files.pythonhosted.org/packages/05/7b/efc5b4134c97f08b161faa703327cde3fe647c5c48c156fde0c343471095/watchdog-4.0.1-py3-none-manylinux2014_armv7l.whl", hash = "sha256:4513ec234c68b14d4161440e07f995f231be21a09329051e67a2118a7a612d2d", size = 83009 }, - { url = "https://files.pythonhosted.org/packages/c3/bb/1fac328ba90ea091ef04e7bdefe638a933076530d802c1b1cf1f03fe7e89/watchdog-4.0.1-py3-none-manylinux2014_i686.whl", hash = "sha256:4107ac5ab936a63952dea2a46a734a23230aa2f6f9db1291bf171dac3ebd53c6", size = 83011 }, - { url = "https://files.pythonhosted.org/packages/ce/df/c8719022af772d9f75f1c49af453a48a785a45295bca1ce4f3f55b9923af/watchdog-4.0.1-py3-none-manylinux2014_ppc64.whl", hash = "sha256:6e8c70d2cd745daec2a08734d9f63092b793ad97612470a0ee4cbb8f5f705c57", size = 83012 }, - { url = "https://files.pythonhosted.org/packages/b0/d5/7285d52e7a7ffce2ae0b21a98dbbed345bcb227672a4268eb26d046d8d41/watchdog-4.0.1-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:f27279d060e2ab24c0aa98363ff906d2386aa6c4dc2f1a374655d4e02a6c5e5e", size = 83011 }, - { url = "https://files.pythonhosted.org/packages/2a/09/4b07dc8dd1a9f67a7acfbc084f26fc35ee8a2e4feeb0a2c98fe9a1ef196c/watchdog-4.0.1-py3-none-manylinux2014_s390x.whl", hash = "sha256:f8affdf3c0f0466e69f5b3917cdd042f89c8c63aebdb9f7c078996f607cdb0f5", size = 83009 }, - { url = "https://files.pythonhosted.org/packages/24/01/a4034a94a5f1828eb050230e7cf13af3ac23cf763512b6afe008d3def97c/watchdog-4.0.1-py3-none-manylinux2014_x86_64.whl", hash = "sha256:ac7041b385f04c047fcc2951dc001671dee1b7e0615cde772e84b01fbf68ee84", size = 83012 }, - { url = "https://files.pythonhosted.org/packages/8f/5e/c0d7dad506adedd584188578901871fe923abf6c0c5dc9e79d9be5c7c24e/watchdog-4.0.1-py3-none-win32.whl", hash = "sha256:206afc3d964f9a233e6ad34618ec60b9837d0582b500b63687e34011e15bb429", size = 82996 }, - { url = "https://files.pythonhosted.org/packages/85/e0/2a9f43008902427b5f074c497705d6ef8f815c85d4bc25fbf83f720a6159/watchdog-4.0.1-py3-none-win_amd64.whl", hash = "sha256:7577b3c43e5909623149f76b099ac49a1a01ca4e167d1785c76eb52fa585745a", size = 83002 }, - { url = "https://files.pythonhosted.org/packages/db/54/23e5845ef68e1817b3792b2a11fb2088d7422814d41af8186d9058c4ff07/watchdog-4.0.1-py3-none-win_ia64.whl", hash = "sha256:d7b9f5f3299e8dd230880b6c55504a1f69cf1e4316275d1b215ebdd8187ec88d", size = 83002 }, -] - -[[distribution]] +version = "4.0.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/4f/38/764baaa25eb5e35c9a043d4c4588f9836edfe52a708950f4b6d5f714fd42/watchdog-4.0.2.tar.gz", hash = "sha256:b4dfbb6c49221be4535623ea4474a4d6ee0a9cef4a80b20c28db4d858b64e270", size = 126587 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/de/78/027ad372d62f97642349a16015394a7680530460b1c70c368c506cb60c09/watchdog-4.0.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7c7d4bf585ad501c5f6c980e7be9c4f15604c7cc150e942d82083b31a7548930", size = 100256 }, + { url = "https://files.pythonhosted.org/packages/59/a9/412b808568c1814d693b4ff1cec0055dc791780b9dc947807978fab86bc1/watchdog-4.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:914285126ad0b6eb2258bbbcb7b288d9dfd655ae88fa28945be05a7b475a800b", size = 92252 }, + { url = "https://files.pythonhosted.org/packages/04/57/179d76076cff264982bc335dd4c7da6d636bd3e9860bbc896a665c3447b6/watchdog-4.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:984306dc4720da5498b16fc037b36ac443816125a3705dfde4fd90652d8028ef", size = 92888 }, + { url = "https://files.pythonhosted.org/packages/92/f5/ea22b095340545faea37ad9a42353b265ca751f543da3fb43f5d00cdcd21/watchdog-4.0.2-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:1cdcfd8142f604630deef34722d695fb455d04ab7cfe9963055df1fc69e6727a", size = 100342 }, + { url = "https://files.pythonhosted.org/packages/cb/d2/8ce97dff5e465db1222951434e3115189ae54a9863aef99c6987890cc9ef/watchdog-4.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:d7ab624ff2f663f98cd03c8b7eedc09375a911794dfea6bf2a359fcc266bff29", size = 92306 }, + { url = "https://files.pythonhosted.org/packages/49/c4/1aeba2c31b25f79b03b15918155bc8c0b08101054fc727900f1a577d0d54/watchdog-4.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:132937547a716027bd5714383dfc40dc66c26769f1ce8a72a859d6a48f371f3a", size = 92915 }, + { url = "https://files.pythonhosted.org/packages/79/63/eb8994a182672c042d85a33507475c50c2ee930577524dd97aea05251527/watchdog-4.0.2-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:cd67c7df93eb58f360c43802acc945fa8da70c675b6fa37a241e17ca698ca49b", size = 100343 }, + { url = "https://files.pythonhosted.org/packages/ce/82/027c0c65c2245769580605bcd20a1dc7dfd6c6683c8c4e2ef43920e38d27/watchdog-4.0.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:bcfd02377be80ef3b6bc4ce481ef3959640458d6feaae0bd43dd90a43da90a7d", size = 92313 }, + { url = "https://files.pythonhosted.org/packages/2a/89/ad4715cbbd3440cb0d336b78970aba243a33a24b1a79d66f8d16b4590d6a/watchdog-4.0.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:980b71510f59c884d684b3663d46e7a14b457c9611c481e5cef08f4dd022eed7", size = 92919 }, + { url = "https://files.pythonhosted.org/packages/8a/b1/25acf6767af6f7e44e0086309825bd8c098e301eed5868dc5350642124b9/watchdog-4.0.2-py3-none-manylinux2014_aarch64.whl", hash = "sha256:936acba76d636f70db8f3c66e76aa6cb5136a936fc2a5088b9ce1c7a3508fc83", size = 82947 }, + { url = "https://files.pythonhosted.org/packages/e8/90/aebac95d6f954bd4901f5d46dcd83d68e682bfd21798fd125a95ae1c9dbf/watchdog-4.0.2-py3-none-manylinux2014_armv7l.whl", hash = "sha256:e252f8ca942a870f38cf785aef420285431311652d871409a64e2a0a52a2174c", size = 82942 }, + { url = "https://files.pythonhosted.org/packages/15/3a/a4bd8f3b9381824995787488b9282aff1ed4667e1110f31a87b871ea851c/watchdog-4.0.2-py3-none-manylinux2014_i686.whl", hash = "sha256:0e83619a2d5d436a7e58a1aea957a3c1ccbf9782c43c0b4fed80580e5e4acd1a", size = 82947 }, + { url = "https://files.pythonhosted.org/packages/09/cc/238998fc08e292a4a18a852ed8274159019ee7a66be14441325bcd811dfd/watchdog-4.0.2-py3-none-manylinux2014_ppc64.whl", hash = "sha256:88456d65f207b39f1981bf772e473799fcdc10801062c36fd5ad9f9d1d463a73", size = 82946 }, + { url = "https://files.pythonhosted.org/packages/80/f1/d4b915160c9d677174aa5fae4537ae1f5acb23b3745ab0873071ef671f0a/watchdog-4.0.2-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:32be97f3b75693a93c683787a87a0dc8db98bb84701539954eef991fb35f5fbc", size = 82947 }, + { url = "https://files.pythonhosted.org/packages/db/02/56ebe2cf33b352fe3309588eb03f020d4d1c061563d9858a9216ba004259/watchdog-4.0.2-py3-none-manylinux2014_s390x.whl", hash = "sha256:c82253cfc9be68e3e49282831afad2c1f6593af80c0daf1287f6a92657986757", size = 82944 }, + { url = "https://files.pythonhosted.org/packages/01/d2/c8931ff840a7e5bd5dcb93f2bb2a1fd18faf8312e9f7f53ff1cf76ecc8ed/watchdog-4.0.2-py3-none-manylinux2014_x86_64.whl", hash = "sha256:c0b14488bd336c5b1845cee83d3e631a1f8b4e9c5091ec539406e4a324f882d8", size = 82947 }, + { url = "https://files.pythonhosted.org/packages/d0/d8/cdb0c21a4a988669d7c210c75c6a2c9a0e16a3b08d9f7e633df0d9a16ad8/watchdog-4.0.2-py3-none-win32.whl", hash = "sha256:0d8a7e523ef03757a5aa29f591437d64d0d894635f8a50f370fe37f913ce4e19", size = 82935 }, + { url = "https://files.pythonhosted.org/packages/99/2e/b69dfaae7a83ea64ce36538cc103a3065e12c447963797793d5c0a1d5130/watchdog-4.0.2-py3-none-win_amd64.whl", hash = "sha256:c344453ef3bf875a535b0488e3ad28e341adbd5a9ffb0f7d62cefacc8824ef2b", size = 82934 }, + { url = "https://files.pythonhosted.org/packages/b0/0b/43b96a9ecdd65ff5545b1b13b687ca486da5c6249475b1a45f24d63a1858/watchdog-4.0.2-py3-none-win_ia64.whl", hash = "sha256:baececaa8edff42cd16558a639a9b0ddf425f93d892e8392a56bf904f5eff22c", size = 82933 }, +] + +[[package]] name = "websocket-client" version = "1.8.0" source = { registry = "https://pypi.org/simple" } @@ -5283,27 +5393,27 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/5a/84/44687a29792a70e111c5c477230a72c4b957d88d16141199bf9acb7537a3/websocket_client-1.8.0-py3-none-any.whl", hash = "sha256:17b44cc997f5c498e809b22cdf2d9c7a9e71c02c8cc2b6c56e7c2d1239bfa526", size = 58826 }, ] -[[distribution]] +[[package]] name = "yapf" version = "0.40.2" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "importlib-metadata", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "platformdirs", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "tomli", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "importlib-metadata" }, + { name = "platformdirs" }, + { name = "tomli" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b9/14/c1f0ebd083fddd38a7c832d5ffde343150bd465689d12c549c303fbcd0f5/yapf-0.40.2.tar.gz", hash = "sha256:4dab8a5ed7134e26d57c1647c7483afb3f136878b579062b786c9ba16b94637b", size = 252068 } wheels = [ { url = "https://files.pythonhosted.org/packages/66/c9/d4b03b2490107f13ebd68fe9496d41ae41a7de6275ead56d0d4621b11ffd/yapf-0.40.2-py3-none-any.whl", hash = "sha256:adc8b5dd02c0143108878c499284205adb258aad6db6634e5b869e7ee2bd548b", size = 254707 }, ] -[[distribution]] +[[package]] name = "yarl" version = "1.9.4" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "idna", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, - { name = "multidict", marker = "python_version == '3.11' or python_version >= '3.12' or (python_version < '3.12' and (python_version < '3.11' or python_version > '3.11'))" }, + { name = "idna" }, + { name = "multidict" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e0/ad/bedcdccbcbf91363fd425a948994f3340924145c2bc8ccb296f4a1e52c28/yarl-1.9.4.tar.gz", hash = "sha256:566db86717cf8080b99b58b083b773a908ae40f06681e87e589a976faf8246bf", size = 141869 } wheels = [ @@ -5340,16 +5450,16 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/4d/05/4d79198ae568a92159de0f89e710a8d19e3fa267b719a236582eee921f4a/yarl-1.9.4-py3-none-any.whl", hash = "sha256:928cecb0ef9d5a7946eb6ff58417ad2fe9375762382f1bf5c55e61645f2c43ad", size = 31638 }, ] -[[distribution]] +[[package]] name = "zipp" -version = "3.19.2" +version = "3.20.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d3/20/b48f58857d98dcb78f9e30ed2cfe533025e2e9827bbd36ea0a64cc00cbc1/zipp-3.19.2.tar.gz", hash = "sha256:bf1dcf6450f873a13e952a29504887c89e6de7506209e5b1bcc3460135d4de19", size = 22922 } +sdist = { url = "https://files.pythonhosted.org/packages/0e/af/9f2de5bd32549a1b705af7a7c054af3878816a1267cb389c03cc4f342a51/zipp-3.20.0.tar.gz", hash = "sha256:0145e43d89664cfe1a2e533adc75adafed82fe2da404b4bbb6b026c0157bdb31", size = 23244 } wheels = [ - { url = "https://files.pythonhosted.org/packages/20/38/f5c473fe9b90c8debdd29ea68d5add0289f1936d6f923b6b9cc0b931194c/zipp-3.19.2-py3-none-any.whl", hash = "sha256:f091755f667055f2d02b32c53771a7a6c8b47e1fdbc4b72a8b9072b3eef8015c", size = 9039 }, + { url = "https://files.pythonhosted.org/packages/da/cc/b9958af9f9c86b51f846d8487440af495ecf19b16e426fce1ed0b0796175/zipp-3.20.0-py3-none-any.whl", hash = "sha256:58da6168be89f0be59beb194da1250516fdaa062ccebd30127ac65d30045e10d", size = 9432 }, ] -[[distribution]] +[[package]] name = "zstandard" version = "0.23.0" source = { registry = "https://pypi.org/simple" }