diff --git a/.github/workflows/badges.yaml b/.github/workflows/badges.yaml index 223c7348631f8f..16edb45c21cf6b 100644 --- a/.github/workflows/badges.yaml +++ b/.github/workflows/badges.yaml @@ -7,12 +7,7 @@ on: env: BASE_IMAGE: openpilot-base DOCKER_REGISTRY: ghcr.io/commaai - - BUILD: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true - docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true - docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . - RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c + RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $DOCKER_REGISTRY/$BASE_IMAGE:latest /bin/sh -c jobs: badges: @@ -23,23 +18,7 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - - name: Build Docker image - run: eval "$BUILD" - + - uses: ./.github/workflows/setup - name: Push badges run: | ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/ui/translations/create_badges.py" @@ -49,6 +28,6 @@ jobs: git config user.email "badge-researcher@comma.ai" git config user.name "Badge Researcher" - git add translation_badge_*.svg + git add translation_badge.svg git commit -m "Add/Update badges" git push -f origin HEAD diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 7397e30f832971..8529da8e89fb1f 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -17,7 +17,7 @@ env: docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . - RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c + RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e FILEREADER_CACHE=1 -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c BUILD_CL: | docker pull $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest || true @@ -27,11 +27,10 @@ env: UNIT_TEST: coverage run --append -m unittest discover jobs: - # TODO: once actions/cache supports read only mode, use the cache for all jobs build_release: name: build release runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 30 env: STRIPPED_DIR: /tmp/releasepilot steps: @@ -39,44 +38,29 @@ jobs: with: fetch-depth: 0 submodules: true - - name: Pull LFS - run: git lfs pull + - name: Build devel + run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh + - uses: ./.github/workflows/setup - name: Check submodules if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' run: release/check-submodules.sh - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build devel + - name: Build openpilot and run checks + run: | + cd $STRIPPED_DIR + ${{ env.RUN }} "CI=1 python selfdrive/manager/build.py" + - name: Run tests run: | - TARGET_DIR=$STRIPPED_DIR release/build_devel.sh - cp Dockerfile.openpilot_base $STRIPPED_DIR + cd $STRIPPED_DIR + ${{ env.RUN }} "release/check-dirty.sh && \ + python -m unittest discover selfdrive/car" + - name: pre-commit + run: | + cd $GITHUB_WORKSPACE cp .pre-commit-config.yaml $STRIPPED_DIR cp .pylintrc $STRIPPED_DIR cp mypy.ini $STRIPPED_DIR - - name: Build Docker image - run: | - eval "$BUILD" - rm $STRIPPED_DIR/Dockerfile.openpilot_base - - name: Build openpilot and run checks - run: | - cd $STRIPPED_DIR - ${{ env.RUN }} "CI=1 python selfdrive/manager/build.py && \ - pre-commit run --all && \ - rm .pre-commit-config.yaml && \ - rm .pylintrc && \ - rm mypy.ini && \ - release/check-dirty.sh && \ - python -m unittest discover selfdrive/car" + cd $STRIPPED_DIR + ${{ env.RUN }} "pre-commit run --all" build_all: name: build all @@ -86,26 +70,14 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: ${{ github.ref != 'refs/heads/master' || github.repository != 'commaai/openpilot' }} + - uses: ./.github/workflows/setup with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}-${{ steps.date.outputs.time }} - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + save-cache: true - name: Build openpilot with all flags run: ${{ env.RUN }} "scons -j$(nproc) --extras --test && release/check-dirty.sh" - name: Cleanup scons cache run: | - ${{ env.RUN }} "scons -j$(nproc) --extras --test && \ - rm -rf /tmp/scons_cache/* && \ + ${{ env.RUN }} "rm -rf /tmp/scons_cache/* && \ scons -j$(nproc) --extras --test --cache-populate" #build_mac: @@ -175,21 +147,9 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- + - uses: ./.github/workflows/setup - name: Build Docker image run: | - eval "$BUILD" docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true docker build --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f tools/webcam/Dockerfile . - name: Build openpilot @@ -244,30 +204,11 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache dependencies - id: dependency-cache - uses: actions/cache@v2 - with: - path: /tmp/comma_download_cache - key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/test_valgrind_replay.py') }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Run valgrind run: | ${{ env.RUN }} "scons -j$(nproc) && \ - FILEREADER_CACHE=1 python selfdrive/test/test_valgrind_replay.py" + python selfdrive/test/test_valgrind_replay.py" - name: Print logs if: always() run: cat selfdrive/test/valgrind_logs.txt @@ -277,28 +218,10 @@ jobs: runs-on: ubuntu-20.04 timeout-minutes: 50 steps: - - name: Get current date - id: date - run: echo "::set-output name=time::$(date +'%s')" - - name: Output timestamp - run: echo $TIMESTAMP - env: - TIMESTAMP: ${{ steps.date.outputs.time }} - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: ${{ github.ref != 'refs/heads/master' || github.repository != 'commaai/openpilot' }} - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}-${{ steps.date.outputs.time }} - restore-keys: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Run unit tests run: | ${{ env.RUN }} "export SKIP_LONG_TESTS=1 && \ @@ -339,30 +262,17 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache dependencies + - uses: ./.github/workflows/setup + - name: Cache test routes id: dependency-cache - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: /tmp/comma_download_cache - key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/test_processes.py') }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + key: proc-replay-${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/ref_commit') }} - name: Run replay run: | ${{ env.RUN }} "scons -j$(nproc) && \ - FILEREADER_CACHE=1 CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \ + CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \ coverage xml" - name: Print diff if: always() @@ -389,35 +299,16 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Pull LFS - run: git lfs pull - - name: Cache dependencies - id: dependency-cache - uses: actions/cache@v2 - with: - path: /tmp/comma_download_cache - key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/model_replay.py') }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- + - uses: ./.github/workflows/setup - name: Build Docker image - # Sim docker is needed to get the intel OPENCL drivers + # Sim docker is needed to get the OpenCL drivers run: eval "$BUILD_CL" - name: Run replay run: | ${{ env.RUN_CL }} "scons -j$(nproc) && \ - ONNXCPU=1 FILEREADER_CACHE=1 CI=1 coverage run \ - selfdrive/test/process_replay/model_replay.py -j$(nproc) && \ - coverage xml" + ONNXCPU=1 CI=1 coverage run \ + selfdrive/test/process_replay/model_replay.py -j$(nproc) && \ + coverage xml" test_longitudinal: name: longitudinal @@ -427,20 +318,7 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Test longitudinal run: | ${{ env.RUN }} "mkdir -p selfdrive/test/out && \ @@ -469,30 +347,17 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache dependencies + - uses: ./.github/workflows/setup + - name: Cache test routes id: dependency-cache - uses: actions/cache@v2 + uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b with: path: /tmp/comma_download_cache key: car_models-${{ hashFiles('selfdrive/car/tests/test_models.py', 'selfdrive/car/tests/routes.py') }}-${{ matrix.job }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" - name: Test car models run: | ${{ env.RUN }} "scons -j$(nproc) --test && \ - FILEREADER_CACHE=1 coverage run -m pytest selfdrive/car/tests/test_models.py && \ + coverage run -m pytest selfdrive/car/tests/test_models.py && \ coverage xml && \ chmod -R 777 /tmp/comma_download_cache" env: @@ -530,20 +395,7 @@ jobs: with: submodules: true ref: ${{ github.event.pull_request.base.ref }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Get base car info run: | ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/debug/dump_car_info.py --path /tmp/openpilot_cache/base_car_info" diff --git a/.github/workflows/setup/action.yaml b/.github/workflows/setup/action.yaml new file mode 100644 index 00000000000000..79ec9212354c26 --- /dev/null +++ b/.github/workflows/setup/action.yaml @@ -0,0 +1,45 @@ +name: 'openpilot env setup' + +env: + BASE_IMAGE: openpilot-base + DOCKER_REGISTRY: ghcr.io/commaai + BUILD: | + docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true + docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true + docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . + +inputs: + save-cache: + default: false + required: false + +runs: + using: "composite" + steps: + # do this after checkout to ensure our custom LFS config is used to pull from GitLab + - shell: bash + run: git lfs pull + + # build cache + - id: date + shell: bash + run: echo "::set-output name=date::$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d')" + - shell: bash + run: echo "${{ steps.date.outputs.date }}" + - shell: bash + run: echo "CACHE_SKIP_SAVE=true" >> $GITHUB_ENV + if: github.ref != 'refs/heads/master' || inputs.save-cache == 'false' + - id: scons-cache + # TODO: change the version to the released version + # when https://github.com/actions/cache/pull/489 (or 571) is merged. + uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b + with: + path: /tmp/scons_cache + key: scons-${{ steps.date.outputs.date }}-${{ github.sha }} + restore-keys: | + scons-${{ steps.date.outputs.date }}- + scons- + + # build our docker image + - shell: bash + run: eval "$BUILD" diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index e93ce2bb39a146..173e2083847264 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -21,46 +21,6 @@ env: GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c jobs: - build_latest_ubuntu: - name: build latest ubuntu - runs-on: ubuntu-20.04 - timeout-minutes: 60 - steps: - - uses: actions/checkout@v3 - with: - submodules: true - - name: Cache pyenv - id: ubuntu-latest-pyenv - uses: actions/cache@v3 - with: - path: | - ~/.pyenv - ~/.local/share/virtualenvs/ - key: ubuntu-latest-python-${{ hashFiles('tools/ubuntu_setup.sh') }}- - - name: Cache scons - id: ubuntu-latest-scons - uses: actions/cache@v3 - with: - path: /tmp/scons_cache - key: ubuntu-latest-scons-${{ hashFiles('.github/workflows/tools_test.yaml') }}- - restore-keys: | - ubuntu-latest-scons-${{ hashFiles('.github/workflows/tools_test.yaml') }}- - ubuntu-latest-scons- - - - name: tools/ubuntu_setup.sh - run: | - source tools/openpilot_env.sh - tools/ubuntu_setup.sh - - name: Build openpilot - run: | - source tools/openpilot_env.sh - pipenv run scons -j$(nproc) --extras --test - - name: Cleanup scons cache - run: | - source tools/openpilot_env.sh - rm -rf /tmp/scons_cache/* - pipenv run scons -j$(nproc) --extras --test --cache-populate - plotjuggler: name: plotjuggler runs-on: ubuntu-20.04 diff --git a/README.md b/README.md index 94837575b456e9..0b6fc20105ba26 100755 --- a/README.md +++ b/README.md @@ -17,7 +17,7 @@ Table of Contents What is openpilot? ------ -[openpilot](http://github.com/commaai/openpilot) is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW) and Lane Departure Warning (LDW) for a growing variety of [supported car makes, models and model years](docs/CARS.md). In addition, while openpilot is engaged, a camera based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about [the vehicle integration](docs/INTEGRATION.md) and [limitations](docs/LIMITATIONS.md). +[openpilot](http://github.com/commaai/openpilot) is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW), and Lane Departure Warning (LDW) for a growing variety of [supported car makes, models, and model years](docs/CARS.md). In addition, while openpilot is engaged, a camera-based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about [the vehicle integration](docs/INTEGRATION.md) and [limitations](docs/LIMITATIONS.md). @@ -40,9 +40,9 @@ Running on a dedicated device in a car To use openpilot in a car, you need four things * A supported device to run this software: a [comma three](https://comma.ai/shop/products/three). -* This software. The setup procedure of the comma three allows the user to enter a url for custom software. -The url, openpilot.comma.ai will install the release version of openpilot. To install openpilot master, you can use installer.comma.ai/commaai/master, and replacing commaai with another github username can install a fork. -* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported, but has adaptive cruise control and lane keeping assist, it's likely able to run openpilot. +* This software. The setup procedure of the comma three allows the user to enter a URL for custom software. +The URL, openpilot.comma.ai will install the release version of openpilot. To install openpilot master, you can use installer.comma.ai/commaai/master, and replacing commaai with another GitHub username can install a fork. +* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported but has adaptive cruise control and lane-keeping assist, it's likely able to run openpilot. * A [car harness](https://comma.ai/shop/products/car-harness) to connect to your car. We have detailed instructions for [how to mount the device in a car](https://comma.ai/setup). @@ -52,11 +52,11 @@ Running on PC All of openpilot's services can run as normal on a PC, even without special hardware or a car. To develop or experiment with openpilot you can run openpilot on recorded or simulated data. -With openpilot's tools you can plot logs, replay drives and watch the full-res camera streams. See [the tools README](tools/README.md) for more information. +With openpilot's tools, you can plot logs, replay drives, and watch the full-res camera streams. See [the tools README](tools/README.md) for more information. -You can also run openpilot in simulation [with the CARLA simulator](tools/sim/README.md). This allows openpilot to drive around a virtual car on your Ubuntu machine. The whole setup should only take a few minutes, but does require a decent GPU. +You can also run openpilot in simulation [with the CARLA simulator](tools/sim/README.md). This allows openpilot to drive around a virtual car on your Ubuntu machine. The whole setup should only take a few minutes but does require a decent GPU. -A PC running openpilot can also control your vehicle if it is connected to a [a webcam](https://github.com/commaai/openpilot/tree/master/tools/webcam), a [black panda](https://comma.ai/shop/products/panda), and [a harness](https://comma.ai/shop/products/car-harness). +A PC running openpilot can also control your vehicle if it is connected to a [webcam](https://github.com/commaai/openpilot/tree/master/tools/webcam), a [black panda](https://comma.ai/shop/products/panda), and a [harness](https://comma.ai/shop/products/car-harness). Community and Contributing ------ @@ -78,8 +78,8 @@ By default, openpilot uploads the driving data to our servers. You can also acce openpilot is open source software: the user is free to disable data collection if they wish to do so. -openpilot logs the road facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. -The driver facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. +openpilot logs the road-facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +The driver-facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. By using openpilot, you agree to [our Privacy Policy](https://comma.ai/privacy). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma for the use of this data. @@ -87,11 +87,11 @@ Safety and Testing ---- * openpilot observes ISO26262 guidelines, see [SAFETY.md](docs/SAFETY.md) for more details. -* openpilot has software in the loop [tests](.github/workflows/selfdrive_tests.yaml) that run on every commit. +* openpilot has software-in-the-loop [tests](.github/workflows/selfdrive_tests.yaml) that run on every commit. * The code enforcing the safety model lives in panda and is written in C, see [code rigor](https://github.com/commaai/panda#code-rigor) for more details. -* panda has software in the loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). -* Internally, we have a hardware in the loop Jenkins test suite that builds and unit tests the various processes. -* panda has additional hardware in the loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). +* panda has software-in-the-loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). +* Internally, we have a hardware-in-the-loop Jenkins test suite that builds and unit tests the various processes. +* panda has additional hardware-in-the-loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). * We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes. Directory Structure diff --git a/RELEASES.md b/RELEASES.md index ced165fb0d0200..3ac6c8e41dfe69 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,11 +1,21 @@ -Version 0.8.16 (2022-XX-XX) +Version 0.8.17 (2022-XX-XX) +======================== + +Version 0.8.16 (2022-08-26) ======================== * New driving model * Reduced turn cutting * Auto-detect right hand drive setting with driver monitoring model +* Improved fan controller for comma three +* New translations + * Japanese thanks to cydia2020! + * Brazilian Portuguese thanks to AlexandreSato! * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! +* Chevrolet Silverado 1500 2020-21 support thanks to JasonJShuler! +* GMC Sierra 1500 2020-21 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! +* Hyundai Tucson Hybrid 2022 support thanks to sunnyhaibin! * Subaru Legacy 2020-22 support thanks to martinl! * Subaru Outback 2020-22 support diff --git a/cereal b/cereal index ecff0a284a2aa9..589ef049a7b0ba 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit ecff0a284a2aa9879c4d04ea797356e4ef024dc4 +Subproject commit 589ef049a7b0bac31f4c8987c0fc539839fae489 diff --git a/common/version.h b/common/version.h index bf1c58df1e2920..0a109c1faac060 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.16" +#define COMMA_VERSION "0.8.17" diff --git a/docs/CARS.md b/docs/CARS.md index efd9b3c5201129..78b4d3b168305e 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -2,9 +2,9 @@ # Supported Cars -A supported vehicle is one that just works when you install a comma device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. +A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system. -# 202 Supported Cars +# 205 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -18,7 +18,8 @@ A supported vehicle is one that just works when you install a comma device. Ever |Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| |Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| -|Chevrolet|Bolt EUV 2022-23|Premier/Premier Redline Trim|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| |Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| @@ -31,6 +32,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| |Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| |Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| @@ -76,6 +78,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Hyundai|Tucson 2021|Smart Cruise Control (SCC)|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai N| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| @@ -227,13 +230,13 @@ Although they're not upstream, the community has openpilot running on other make # Don't see your car here? **openpilot can support many more cars than it currently does.** There are a few reasons your car may not be supported. -If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. We don't have a roadmap for car support, and in fact, most car support comes from users like you! +If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. **We don't have a roadmap for car support**, and in fact, most car support comes from users like you! ### Which cars are able to be supported? -openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering) and [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control), then it almost certainly has these interfaces. These interfaces generally started shipping on cars around 2016. +openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control) and any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering), then it almost certainly has these interfaces. These features generally started shipping on cars around 2016. Note that manufacturers will often make their own [marketing terms](https://en.wikipedia.org/wiki/Adaptive_cruise_control#Vehicle_models_supporting_adaptive_cruise_control) for these features, such as Hyundai's "Smart Cruise Control" branding of Adaptive Cruise Control. -If your car has the following packages or features, then it's a good candidate for support. If it does not, then it's unlikely able to be supported. +If your car has the following packages or features, then it's a good candidate for support. | Make | Required Package/Features | | ---- | ------------------------- | @@ -251,8 +254,9 @@ All the cars that openpilot supports use a [CAN bus](https://en.wikipedia.org/wi ### Toyota Security -Specific new Toyota models are shipping with a new message authentication method that openpilot does not yet support. -So far, this list includes: +openpilot does not yet support these Toyota models due to a new message authentication method. +[Vote](https://comma.ai/shop/products/vote) if you'd like to see openpilot support on these models. + * Toyota RAV4 Prime 2021+ * Toyota Sienna 2021+ * Toyota Venza 2021+ @@ -261,4 +265,4 @@ So far, this list includes: * Toyota Corolla Cross 2022+ (only US model) * Lexus NX 2022+ * Toyota bZ4x 2023+ -* Subaru Solterra 2023+ \ No newline at end of file +* Subaru Solterra 2023+ diff --git a/opendbc b/opendbc index 7e095a90af3d36..b913296c912344 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 7e095a90af3d36e6db9128a80f6f3b0cca01efa2 +Subproject commit b913296c9123441b2b271c00239929ed388169b5 diff --git a/panda b/panda index ba8772123f1312..9d6496ece8465d 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit ba8772123f13123c797234660c56adb70795cebb +Subproject commit 9d6496ece8465dfe30997b31dfb352e1e51dde6c diff --git a/release/files_common b/release/files_common index ac2a3ce6266dd2..663d6d35529551 100644 --- a/release/files_common +++ b/release/files_common @@ -513,6 +513,8 @@ opendbc/gm_global_a_powertrain_generated.dbc opendbc/gm_global_a_object.dbc opendbc/gm_global_a_chassis.dbc +opendbc/FORD_CADS.dbc +opendbc/ford_fusion_2018_adas.dbc opendbc/ford_lincoln_base_pt.dbc opendbc/honda_accord_2018_can_generated.dbc diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py deleted file mode 100755 index fad29f6f34ae37..00000000000000 --- a/selfdrive/boardd/tests/boardd_old.py +++ /dev/null @@ -1,245 +0,0 @@ -#!/usr/bin/env python3 -# pylint: skip-file - -# This file is not used by openpilot. Only boardd.cc is used. -# The python version is slower, but has more options for development. - -# TODO: merge the extra functionalities of this file (like MOCK) in boardd.c and -# delete this python version of boardd - -import os -import struct -import time - -import cereal.messaging as messaging -from common.realtime import Ratekeeper -from system.swaglog import cloudlog -from selfdrive.boardd.boardd import can_capnp_to_can_list -from cereal import car - -SafetyModel = car.CarParams.SafetyModel - -# USB is optional -try: - import usb1 - from usb1 import USBErrorIO, USBErrorOverflow # pylint: disable=no-name-in-module -except Exception: - pass - -# *** serialization functions *** -def can_list_to_can_capnp(can_msgs, msgtype='can'): - dat = messaging.new_message(msgtype, len(can_msgs)) - for i, can_msg in enumerate(can_msgs): - if msgtype == 'sendcan': - cc = dat.sendcan[i] - else: - cc = dat.can[i] - cc.address = can_msg[0] - cc.busTime = can_msg[1] - cc.dat = bytes(can_msg[2]) - cc.src = can_msg[3] - return dat - - -# *** can driver *** -def can_health(): - while 1: - try: - dat = handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd2, 0, 0, 0x16) - break - except (USBErrorIO, USBErrorOverflow): - cloudlog.exception("CAN: BAD HEALTH, RETRYING") - v, i = struct.unpack("II", dat[0:8]) - ign_line, ign_can = struct.unpack("BB", dat[20:22]) - return {"voltage": v, "current": i, "ignition_line": bool(ign_line), "ignition_can": bool(ign_can)} - -def __parse_can_buffer(dat): - ret = [] - for j in range(0, len(dat), 0x10): - ddat = dat[j:j+0x10] - f1, f2 = struct.unpack("II", ddat[0:8]) - ret.append((f1 >> 21, f2 >> 16, ddat[8:8 + (f2 & 0xF)], (f2 >> 4) & 0xFF)) - return ret - -def can_send_many(arr): - snds = [] - for addr, _, dat, alt in arr: - if addr < 0x800: # only support 11 bit addr - snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat - snd = snd.ljust(0x10, b'\x00') - snds.append(snd) - while 1: - try: - handle.bulkWrite(3, b''.join(snds)) - break - except (USBErrorIO, USBErrorOverflow): - cloudlog.exception("CAN: BAD SEND MANY, RETRYING") - -def can_recv(): - dat = b"" - while 1: - try: - dat = handle.bulkRead(1, 0x10*256) - break - except (USBErrorIO, USBErrorOverflow): - cloudlog.exception("CAN: BAD RECV, RETRYING") - return __parse_can_buffer(dat) - -def can_init(): - global handle, context - handle = None - cloudlog.info("attempting can init") - - context = usb1.USBContext() - #context.setDebug(9) - - for device in context.getDeviceList(skip_on_error=True): - if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc: - handle = device.open() - handle.claimInterface(0) - handle.controlWrite(0x40, 0xdc, SafetyModel.allOutput, 0, b'') - - if handle is None: - cloudlog.warning("CAN NOT FOUND") - exit(-1) - - cloudlog.info("got handle") - cloudlog.info("can init done") - -def boardd_mock_loop(): - can_init() - handle.controlWrite(0x40, 0xdc, SafetyModel.allOutput, 0, b'') - - logcan = messaging.sub_sock('can') - sendcan = messaging.pub_sock('sendcan') - - while 1: - tsc = messaging.drain_sock(logcan, wait_for_one=True) - snds = map(lambda x: can_capnp_to_can_list(x.can), tsc) - snd = [] - for s in snds: - snd += s - snd = list(filter(lambda x: x[-1] <= 2, snd)) - snd_0 = len(list(filter(lambda x: x[-1] == 0, snd))) - snd_1 = len(list(filter(lambda x: x[-1] == 1, snd))) - snd_2 = len(list(filter(lambda x: x[-1] == 2, snd))) - can_send_many(snd) - - # recv @ 100hz - can_msgs = can_recv() - got_0 = len(list(filter(lambda x: x[-1] == 0+0x80, can_msgs))) - got_1 = len(list(filter(lambda x: x[-1] == 1+0x80, can_msgs))) - got_2 = len(list(filter(lambda x: x[-1] == 2+0x80, can_msgs))) - print("sent %3d (%3d/%3d/%3d) got %3d (%3d/%3d/%3d)" % - (len(snd), snd_0, snd_1, snd_2, len(can_msgs), got_0, got_1, got_2)) - m = can_list_to_can_capnp(can_msgs, msgtype='sendcan') - sendcan.send(m.to_bytes()) - -def boardd_test_loop(): - can_init() - cnt = 0 - while 1: - can_send_many([[0xbb, 0, "\xaa\xaa\xaa\xaa", 0], [0xaa, 0, "\xaa\xaa\xaa\xaa"+struct.pack("!I", cnt), 1]]) - #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",0]]) - #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",1]]) - # recv @ 100hz - can_msgs = can_recv() - print("got %d" % (len(can_msgs))) - time.sleep(0.01) - cnt += 1 - -# *** main loop *** -def boardd_loop(rate=100): - rk = Ratekeeper(rate) - - can_init() - - # *** publishes can and health - logcan = messaging.pub_sock('can') - health_sock = messaging.pub_sock('pandaStates') - - # *** subscribes to can send - sendcan = messaging.sub_sock('sendcan') - - # drain sendcan to delete any stale messages from previous runs - messaging.drain_sock(sendcan) - - while 1: - # health packet @ 2hz - if (rk.frame % (rate // 2)) == 0: - health = can_health() - msg = messaging.new_message('pandaStates', 1) - - # store the health to be logged - msg.pandaState[0].voltage = health['voltage'] - msg.pandaState[0].current = health['current'] - msg.pandaState[0].ignitionLine = health['ignition_line'] - msg.pandaState[0].ignitionCan = health['ignition_can'] - msg.pandaState[0].controlsAllowed = True - - health_sock.send(msg.to_bytes()) - - # recv @ 100hz - can_msgs = can_recv() - - # publish to logger - # TODO: refactor for speed - if len(can_msgs) > 0: - dat = can_list_to_can_capnp(can_msgs).to_bytes() - logcan.send(dat) - - # send can if we have a packet - tsc = messaging.recv_sock(sendcan) - if tsc is not None: - can_send_many(can_capnp_to_can_list(tsc.sendcan)) - - rk.keep_time() - -# *** main loop *** -def boardd_proxy_loop(rate=100, address="192.168.2.251"): - rk = Ratekeeper(rate) - - can_init() - - # *** subscribes can - logcan = messaging.sub_sock('can', addr=address) - # *** publishes to can send - sendcan = messaging.pub_sock('sendcan') - - # drain sendcan to delete any stale messages from previous runs - messaging.drain_sock(sendcan) - - while 1: - # recv @ 100hz - can_msgs = can_recv() - #for m in can_msgs: - # print("R: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex"))) - - # publish to logger - # TODO: refactor for speed - if len(can_msgs) > 0: - dat = can_list_to_can_capnp(can_msgs, "sendcan") - sendcan.send(dat) - - # send can if we have a packet - tsc = messaging.recv_sock(logcan) - if tsc is not None: - cl = can_capnp_to_can_list(tsc.can) - #for m in cl: - # print("S: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex"))) - can_send_many(cl) - - rk.keep_time() - -def main(): - if os.getenv("MOCK") is not None: - boardd_mock_loop() - elif os.getenv("PROXY") is not None: - boardd_proxy_loop() - elif os.getenv("BOARDTEST") is not None: - boardd_test_loop() - else: - boardd_loop() - -if __name__ == "__main__": - main() diff --git a/selfdrive/boardd/tests/replay_many.py b/selfdrive/boardd/tests/replay_many.py deleted file mode 100755 index 78aef07497ad14..00000000000000 --- a/selfdrive/boardd/tests/replay_many.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import time -import signal -import traceback -import usb1 -from panda import Panda, PandaDFU -from multiprocessing import Pool - -jungle = "JUNGLE" in os.environ -if jungle: - from panda_jungle import PandaJungle # pylint: disable=import-error - -import cereal.messaging as messaging -from selfdrive.boardd.boardd import can_capnp_to_can_list - -def initializer(): - """Ignore CTRL+C in the worker process. - source: https://stackoverflow.com/a/44869451 """ - signal.signal(signal.SIGINT, signal.SIG_IGN) - -def send_thread(sender_serial): - while True: - try: - if jungle: - sender = PandaJungle(sender_serial) - else: - sender = Panda(sender_serial) - sender.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - sender.set_can_loopback(False) - can_sock = messaging.sub_sock('can') - - while True: - tsc = messaging.recv_one(can_sock) - snd = can_capnp_to_can_list(tsc.can) - snd = list(filter(lambda x: x[-1] <= 2, snd)) - - try: - sender.can_send_many(snd) - except usb1.USBErrorTimeout: - pass - - # Drain panda message buffer - sender.can_recv() - except Exception: - traceback.print_exc() - time.sleep(1) - -if __name__ == "__main__": - if jungle: - serials = PandaJungle.list() - else: - serials = Panda.list() - num_senders = len(serials) - - if num_senders == 0: - print("No senders found. Exiting") - sys.exit(1) - else: - print("%d senders found. Starting broadcast" % num_senders) - - if "FLASH" in os.environ: - for s in PandaDFU.list(): - PandaDFU(s).recover() - - time.sleep(1) - for s in serials: - Panda(s).recover() - Panda(s).flash() - - pool = Pool(num_senders, initializer=initializer) - pool.map_async(send_thread, serials) - - while True: - try: - time.sleep(10) - except KeyboardInterrupt: - pool.terminate() - pool.join() - raise - diff --git a/selfdrive/boardd/tests/test_boardd_api.py b/selfdrive/boardd/tests/test_boardd_api.py deleted file mode 100644 index f2bcd57a6bf27d..00000000000000 --- a/selfdrive/boardd/tests/test_boardd_api.py +++ /dev/null @@ -1,77 +0,0 @@ -import random -import numpy as np - -import selfdrive.boardd.tests.boardd_old as boardd_old -import selfdrive.boardd.boardd as boardd - -from common.realtime import sec_since_boot -from cereal import log -import unittest - - -def generate_random_can_data_list(): - can_list = [] - cnt = random.randint(1, 64) - for _ in range(cnt): - can_data = np.random.bytes(random.randint(1, 8)) - can_list.append([random.randint(0, 128), random.randint(0, 128), can_data, random.randint(0, 128)]) - return can_list, cnt - - -class TestBoarddApiMethods(unittest.TestCase): - def test_correctness(self): - for i in range(1000): - can_list, _ = generate_random_can_data_list() - - # Sendcan - # Old API - m_old = boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes() - # new API - m = boardd.can_list_to_can_capnp(can_list, 'sendcan') - - ev_old = log.Event.from_bytes(m_old) - ev = log.Event.from_bytes(m) - - self.assertEqual(ev_old.which(), ev.which()) - self.assertEqual(len(ev.sendcan), len(ev_old.sendcan)) - for i in range(len(ev.sendcan)): - attrs = ['address', 'busTime', 'dat', 'src'] - for attr in attrs: - self.assertEqual(getattr(ev.sendcan[i], attr, 'new'), getattr(ev_old.sendcan[i], attr, 'old')) - - # Can - m_old = boardd_old.can_list_to_can_capnp(can_list, 'can').to_bytes() - # new API - m = boardd.can_list_to_can_capnp(can_list, 'can') - - ev_old = log.Event.from_bytes(m_old) - ev = log.Event.from_bytes(m) - self.assertEqual(ev_old.which(), ev.which()) - self.assertEqual(len(ev.can), len(ev_old.can)) - for i in range(len(ev.can)): - attrs = ['address', 'busTime', 'dat', 'src'] - for attr in attrs: - self.assertEqual(getattr(ev.can[i], attr, 'new'), getattr(ev_old.can[i], attr, 'old')) - - def test_performance(self): - can_list, _ = generate_random_can_data_list() - recursions = 1000 - - n1 = sec_since_boot() - for _ in range(recursions): - boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes() - n2 = sec_since_boot() - elapsed_old = n2 - n1 - - # print('Old API, elapsed time: {} secs'.format(elapsed_old)) - n1 = sec_since_boot() - for _ in range(recursions): - boardd.can_list_to_can_capnp(can_list) - n2 = sec_since_boot() - elapsed_new = n2 - n1 - # print('New API, elapsed time: {} secs'.format(elapsed_new)) - self.assertTrue(elapsed_new < elapsed_old / 2) - - -if __name__ == '__main__': - unittest.main() diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index d306ca5d92bfe8..2fce0f9036176e 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -5,7 +5,7 @@ # Supported Cars -A supported vehicle is one that just works when you install a comma device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. +A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system. # {{all_car_info | length}} Supported Cars @@ -27,13 +27,13 @@ Although they're not upstream, the community has openpilot running on other make # Don't see your car here? **openpilot can support many more cars than it currently does.** There are a few reasons your car may not be supported. -If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. We don't have a roadmap for car support, and in fact, most car support comes from users like you! +If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. **We don't have a roadmap for car support**, and in fact, most car support comes from users like you! ### Which cars are able to be supported? -openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering) and [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control), then it almost certainly has these interfaces. These interfaces generally started shipping on cars around 2016. +openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control) and any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering), then it almost certainly has these interfaces. These features generally started shipping on cars around 2016. Note that manufacturers will often make their own [marketing terms](https://en.wikipedia.org/wiki/Adaptive_cruise_control#Vehicle_models_supporting_adaptive_cruise_control) for these features, such as Hyundai's "Smart Cruise Control" branding of Adaptive Cruise Control. -If your car has the following packages or features, then it's a good candidate for support. If it does not, then it's unlikely able to be supported. +If your car has the following packages or features, then it's a good candidate for support. | Make | Required Package/Features | | ---- | ------------------------- | @@ -51,8 +51,9 @@ All the cars that openpilot supports use a [CAN bus](https://en.wikipedia.org/wi ### Toyota Security -Specific new Toyota models are shipping with a new message authentication method that openpilot does not yet support. -So far, this list includes: +openpilot does not yet support these Toyota models due to a new message authentication method. +[Vote](https://comma.ai/shop/products/vote) if you'd like to see openpilot support on these models. + * Toyota RAV4 Prime 2021+ * Toyota Sienna 2021+ * Toyota Venza 2021+ @@ -62,3 +63,4 @@ So far, this list includes: * Lexus NX 2022+ * Toyota bZ4x 2023+ * Subaru Solterra 2023+ + diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 795668381c3be6..4d79cbfc765b42 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -8,6 +8,7 @@ from typing import Dict, List from common.basedir import BASEDIR +from selfdrive.car import gen_empty_fingerprint from selfdrive.car.docs_definitions import CarInfo, Column from selfdrive.car.car_helpers import interfaces, get_interface_attr from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR as HKG_RADAR_START_ADDR @@ -29,7 +30,8 @@ def get_all_car_info() -> List[CarInfo]: footnotes = get_all_footnotes() for model, car_info in get_interface_attr("CAR_INFO", combine_brands=True).items(): # Hyundai exception: those with radar have openpilot longitudinal - fingerprint = {0: {}, 1: {HKG_RADAR_START_ADDR: 8}, 2: {}, 3: {}} + fingerprint = gen_empty_fingerprint() + fingerprint[1] = {HKG_RADAR_START_ADDR: 8} CP = interfaces[model][0].get_params(model, fingerprint=fingerprint, disable_radar=True) if CP.dashcamOnly or car_info is None: diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 866602cf09888b..c942703002ff29 100644 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -1,33 +1,63 @@ #!/usr/bin/env python3 +from math import cos, sin from cereal import car -from common.conversions import Conversions as CV from opendbc.can.parser import CANParser -from selfdrive.car.ford.values import CANBUS, DBC +from common.conversions import Conversions as CV +from selfdrive.car.ford.values import CANBUS, DBC, RADAR from selfdrive.car.interfaces import RadarInterfaceBase -RADAR_MSGS = list(range(0x500, 0x540)) +DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) +DELPHI_MRR_RADAR_START_ADDR = 0x120 +DELPHI_MRR_RADAR_MSG_COUNT = 64 -def _create_radar_can_parser(car_fingerprint): - if DBC[car_fingerprint]['radar'] is None: - return None - msg_n = len(RADAR_MSGS) +def _create_delphi_esr_radar_can_parser(): + msg_n = len(DELPHI_ESR_RADAR_MSGS) signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, - RADAR_MSGS * 3)) - checks = list(zip(RADAR_MSGS, [20] * msg_n)) + DELPHI_ESR_RADAR_MSGS * 3)) + checks = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n)) + + return CANParser(RADAR.DELPHI_ESR, signals, checks, CANBUS.radar) + + +def _create_delphi_mrr_radar_can_parser(): + signals = [] + checks = [] + + for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = f"MRR_Detection_{i:03d}" + signals += [ + (f"CAN_DET_VALID_LEVEL_{i:02d}", msg), + (f"CAN_DET_AZIMUTH_{i:02d}", msg), + (f"CAN_DET_RANGE_{i:02d}", msg), + (f"CAN_DET_RANGE_RATE_{i:02d}", msg), + (f"CAN_DET_AMPLITUDE_{i:02d}", msg), + (f"CAN_SCAN_INDEX_2LSB_{i:02d}", msg), + ] + checks += [(msg, 20)] + + return CANParser(RADAR.DELPHI_MRR, signals, checks, CANBUS.radar) - return CANParser(DBC[car_fingerprint]['radar'], signals, checks, CANBUS.radar) class RadarInterface(RadarInterfaceBase): def __init__(self, CP): super().__init__(CP) - self.validCnt = {key: 0 for key in RADAR_MSGS} - self.track_id = 0 - self.rcp = _create_radar_can_parser(CP.carFingerprint) - self.trigger_msg = 0x53f self.updated_messages = set() + self.track_id = 0 + self.radar = DBC[CP.carFingerprint]['radar'] + if self.radar is None: + self.rcp = None + elif self.radar == RADAR.DELPHI_ESR: + self.rcp = _create_delphi_esr_radar_can_parser() + 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() + 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: @@ -45,20 +75,30 @@ def update(self, can_strings): 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.validCnt[ii] = 0 # reset counter + self.valid_cnt[ii] = 0 # reset counter if cpt['X_Rel'] > 0.00001: - self.validCnt[ii] += 1 + self.valid_cnt[ii] += 1 else: - self.validCnt[ii] = max(self.validCnt[ii] - 1, 0) - #print ii, self.validCnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] + 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.validCnt[ii] > 0: + 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 @@ -73,6 +113,36 @@ def update(self, can_strings): if ii in self.pts: del self.pts[ii] - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret + 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}"]) + amplitude = msg[f"CAN_DET_AMPLITUDE_{ii:02d}"] # dBsm [-64|63] + + if valid and 0 < amplitude <= 15: + 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] + + # *** openpilot radar point *** + self.pts[i].dRel = cos(azimuth) * dist # m from front of car + self.pts[i].yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive + self.pts[i].vRel = distRate # m/s + + self.pts[i].measured = True + + else: + del self.pts[i] diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 6b8396cf072ae6..825d515da9cbd6 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -24,6 +24,11 @@ class CarControllerParams: STEER_RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) +class RADAR: + DELPHI_ESR = 'ford_fusion_2018_adas' + DELPHI_MRR = 'FORD_CADS' + + class CANBUS: main = 0 radar = 1 @@ -80,6 +85,6 @@ class CAR: DBC = { - CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', None), - CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', None), + CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), + CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), } diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 10e6027973e60e..977d20c5b3c2e1 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -109,10 +109,10 @@ def update(self, CC, CS): else: # Stock longitudinal, integrated at camera - if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: + if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: if CC.cruiseControl.cancel: self.last_button_frame = self.frame - can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CruiseButtons.CANCEL)) + can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) # Show green icon when LKA torque is applied, and # alarming orange icon when approaching torque limit. diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 0bda7edad97ced..0bba1d29b8c01f 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -16,12 +16,14 @@ def __init__(self, CP): can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] self.lka_steering_cmd_counter = 0 + self.buttons_counter = 0 def update(self, pt_cp, cam_cp, loopback_cp): ret = car.CarState.new_message() self.prev_cruise_buttons = self.cruise_buttons self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] + self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] ret.wheelSpeeds = self.get_wheel_speeds( pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], @@ -109,6 +111,7 @@ def get_can_parser(CP): ("AcceleratorPedal2", "AcceleratorPedal2"), ("CruiseState", "AcceleratorPedal2"), ("ACCButtons", "ASCMSteeringButton"), + ("RollingCounter", "ASCMSteeringButton"), ("SteeringWheelAngle", "PSCMSteeringAngle"), ("SteeringWheelRate", "PSCMSteeringAngle"), ("FLWheelSpd", "EBCMWheelSpdFront"), diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 3a10c4d9dab4ac..20e4c4ab6efb69 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -1,7 +1,10 @@ from selfdrive.car import make_can_msg -def create_buttons(packer, bus, button): - values = {"ACCButtons": button} +def create_buttons(packer, bus, idx, button): + values = { + "ACCButtons": button, + "RollingCounter": idx, + } return packer.make_can_msg("ASCMSteeringButton", bus, values) def create_steering_control(packer, bus, apply_steer, idx, lkas_active): diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 18709a2a8c816b..09d950ea8d0072 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -160,6 +160,15 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, disa ret.steerActuatorDelay = 0.2 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + elif candidate == CAR.SILVERADO: + ret.minEnableSpeed = -1 + ret.mass = 2200. + STD_CARGO_KG + ret.wheelbase = 3.75 + ret.steerRatio = 16.3 + ret.centerToFront = ret.wheelbase * 0.5 + tire_stiffness_factor = 1.0 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index cb9aff172b4ef6..21ede171e04202 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -59,6 +59,7 @@ class CAR: BUICK_REGAL = "BUICK REGAL ESSENCE 2018" ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016" BOLT_EUV = "CHEVROLET BOLT EUV 2022" + SILVERADO = "CHEVROLET SILVERADO 1500 2020" class Footnote(Enum): @@ -83,7 +84,11 @@ class GMCarInfo(CarInfo): CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo"), CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"), - CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier/Premier Redline Trim", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), + CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), + CAR.SILVERADO: [ + GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm), + GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", footnotes=[], harness=Harness.gm), + ], } @@ -157,6 +162,10 @@ class CanBus: { 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, 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, 1930: 7 }], + CAR.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, 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, 1930: 7 + }], } DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) @@ -164,6 +173,6 @@ class CanBus: EV_CAR = {CAR.VOLT, CAR.BOLT_EUV} # We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.BOLT_EUV} +CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO} STEER_THRESHOLD = 1.0 diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index ab1cc9a6cc0e51..ad4f73c011d4b2 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -113,7 +113,7 @@ class HondaCarInfo(CarInfo): HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), ], CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), - CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec), + CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec, video_link="https://youtu.be/-IkImTe1NYE"), CAR.CIVIC_BOSCH: [ HondaCarInfo("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, harness=Harness.bosch_a), HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch_a), diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 60fb46340de664..971330a33516ce 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -5,7 +5,7 @@ from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.hyundai import hyundaicanfd, hyundaican -from selfdrive.car.hyundai.values import Buttons, CarControllerParams, CANFD_CAR, CAR +from selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR VisualAlert = car.CarControl.HUDControl.VisualAlert LongCtrlState = car.CarControl.Actuators.LongControlState @@ -71,22 +71,33 @@ def update(self, CC, CS): if self.CP.carFingerprint in CANFD_CAR: # steering control - can_sends.append(hyundaicanfd.create_lkas(self.packer, CC.enabled, CC.latActive, apply_steer)) + can_sends.append(hyundaicanfd.create_lkas(self.packer, self.CP, CC.enabled, CC.latActive, apply_steer)) - if self.frame % 5 == 0: + # block LFA on HDA2 + if self.frame % 5 == 0 and (self.CP.flags & HyundaiFlags.CANFD_HDA2): can_sends.append(hyundaicanfd.create_cam_0x2a4(self.packer, CS.cam_0x2a4)) - # cruise cancel + # LFA and HDA icons + if self.frame % 2 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_HDA2): + can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, CC.enabled)) + + # button presses if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: + # cruise cancel if CC.cruiseControl.cancel: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) - self.last_button_frame = self.frame + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + can_sends.append(hyundaicanfd.create_cruise_info(self.packer, CS.cruise_info_copy, True)) + self.last_button_frame = self.frame + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) + self.last_button_frame = self.frame # cruise standstill resume elif CC.cruiseControl.resume: - can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) - self.last_button_frame = self.frame + if not (self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): + can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) + self.last_button_frame = self.frame else: # tester present - w/ no response (keeps radar disabled) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 9105f12789f067..eab6e73f1f429b 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -5,7 +5,7 @@ from common.conversions import Conversions as CV from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine -from selfdrive.car.hyundai.values import DBC, FEATURES, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams +from selfdrive.car.hyundai.values import HyundaiFlags, DBC, FEATURES, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams from selfdrive.car.interfaces import CarStateBase PREV_BUTTON_SAMPLES = 8 @@ -20,7 +20,7 @@ def __init__(self, CP): self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) if CP.carFingerprint in CANFD_CAR: - self.shifter_values = can_define.dv["ACCELERATOR"]["GEAR"] + self.shifter_values = can_define.dv["GEAR_SHIFTER"]["GEAR"] elif self.CP.carFingerprint in FEATURES["use_cluster_gears"]: self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]: @@ -136,14 +136,17 @@ def update(self, cp, cp_cam): def update_canfd(self, cp, cp_cam): ret = car.CarState.new_message() - ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. - ret.gasPressed = ret.gas > 1e-3 + if self.CP.flags & HyundaiFlags.CANFD_HDA2: + ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. + else: + ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023. + ret.gasPressed = ret.gas > 1e-5 ret.brakePressed = cp.vl["BRAKE"]["BRAKE_PRESSED"] == 1 ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR_OPEN"] == 1 ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT_LATCHED"] == 0 - gear = cp.vl["ACCELERATOR"]["GEAR"] + gear = cp.vl["GEAR_SHIFTER"]["GEAR"] ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) # TODO: figure out positions @@ -168,16 +171,19 @@ def update_canfd(self, cp, cp_cam): ret.cruiseState.available = True ret.cruiseState.enabled = cp.vl["SCC1"]["CRUISE_ACTIVE"] == 1 - ret.cruiseState.standstill = cp.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 - + cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam speed_factor = CV.MPH_TO_MS if cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] == 1 else CV.KPH_TO_MS - ret.cruiseState.speed = cp.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor + ret.cruiseState.speed = cp_cruise_info.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor + ret.cruiseState.standstill = cp_cruise_info.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 - self.cruise_buttons.extend(cp.vl_all["CRUISE_BUTTONS"]["CRUISE_BUTTONS"]) - self.main_buttons.extend(cp.vl_all["CRUISE_BUTTONS"]["ADAPTIVE_CRUISE_MAIN_BTN"]) - self.buttons_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] + cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" + self.cruise_buttons.extend(cp.vl_all[cruise_btn_msg]["CRUISE_BUTTONS"]) + self.main_buttons.extend(cp.vl_all[cruise_btn_msg]["ADAPTIVE_CRUISE_MAIN_BTN"]) + self.buttons_counter = cp.vl[cruise_btn_msg]["COUNTER"] + self.cruise_info_copy = copy.copy(cp_cruise_info.vl["CRUISE_INFO"]) - self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) + if self.CP.flags & HyundaiFlags.CANFD_HDA2: + self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) return ret @@ -319,9 +325,7 @@ def get_can_parser(CP): @staticmethod def get_cam_can_parser(CP): if CP.carFingerprint in CANFD_CAR: - signals = [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)] - checks = [("CAM_0x2a4", 20)] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 6) + return CarState.get_cam_can_parser_canfd(CP) signals = [ # signal_name, signal_address @@ -374,14 +378,15 @@ def get_cam_can_parser(CP): @staticmethod def get_can_parser_canfd(CP): + + cruise_btn_msg = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" signals = [ ("WHEEL_SPEED_1", "WHEEL_SPEEDS"), ("WHEEL_SPEED_2", "WHEEL_SPEEDS"), ("WHEEL_SPEED_3", "WHEEL_SPEEDS"), ("WHEEL_SPEED_4", "WHEEL_SPEEDS"), - ("ACCELERATOR_PEDAL", "ACCELERATOR"), - ("GEAR", "ACCELERATOR"), + ("GEAR", "GEAR_SHIFTER"), ("BRAKE_PRESSED", "BRAKE"), ("STEERING_RATE", "STEERING_SENSORS"), @@ -390,11 +395,9 @@ def get_can_parser_canfd(CP): ("STEERING_OUT_TORQUE", "MDPS"), ("CRUISE_ACTIVE", "SCC1"), - ("SET_SPEED", "CRUISE_INFO"), - ("CRUISE_STANDSTILL", "CRUISE_INFO"), - ("COUNTER", "CRUISE_BUTTONS"), - ("CRUISE_BUTTONS", "CRUISE_BUTTONS"), - ("ADAPTIVE_CRUISE_MAIN_BTN", "CRUISE_BUTTONS"), + ("COUNTER", cruise_btn_msg), + ("CRUISE_BUTTONS", cruise_btn_msg), + ("ADAPTIVE_CRUISE_MAIN_BTN", cruise_btn_msg), ("DISTANCE_UNIT", "CLUSTER_INFO"), @@ -407,16 +410,64 @@ def get_can_parser_canfd(CP): checks = [ ("WHEEL_SPEEDS", 100), - ("ACCELERATOR", 100), + ("GEAR_SHIFTER", 100), ("BRAKE", 100), ("STEERING_SENSORS", 100), ("MDPS", 100), ("SCC1", 50), - ("CRUISE_INFO", 50), - ("CRUISE_BUTTONS", 50), + (cruise_btn_msg, 50), ("CLUSTER_INFO", 4), ("BLINKERS", 4), ("DOORS_SEATBELTS", 4), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 5) + if CP.flags & HyundaiFlags.CANFD_HDA2: + signals += [ + ("ACCELERATOR_PEDAL", "ACCELERATOR"), + ("GEAR", "ACCELERATOR"), + ("SET_SPEED", "CRUISE_INFO"), + ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ] + checks += [ + ("CRUISE_INFO", 50), + ("ACCELERATOR", 100), + ] + else: + signals += [ + ("ACCELERATOR_PEDAL", "ACCELERATOR_ALT"), + ] + checks += [ + ("ACCELERATOR_ALT", 100), + ] + + bus = 5 if CP.flags & HyundaiFlags.CANFD_HDA2 else 4 + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, bus) + + @staticmethod + def get_cam_can_parser_canfd(CP): + if CP.flags & HyundaiFlags.CANFD_HDA2: + signals = [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)] + checks = [("CAM_0x2a4", 20)] + else: + signals = [ + ("COUNTER", "CRUISE_INFO"), + ("NEW_SIGNAL_1", "CRUISE_INFO"), + ("CRUISE_MAIN", "CRUISE_INFO"), + ("CRUISE_STATUS", "CRUISE_INFO"), + ("CRUISE_INACTIVE", "CRUISE_INFO"), + ("NEW_SIGNAL_2", "CRUISE_INFO"), + ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ("NEW_SIGNAL_3", "CRUISE_INFO"), + ("BYTE11", "CRUISE_INFO"), + ("SET_SPEED", "CRUISE_INFO"), + ("NEW_SIGNAL_4", "CRUISE_INFO"), + ] + + signals += [(f"BYTE{i}", "CRUISE_INFO") for i in range(3, 7)] + signals += [(f"BYTE{i}", "CRUISE_INFO") for i in range(13, 31)] + + checks = [ + ("CRUISE_INFO", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 6) diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py index 36207aa113280d..a53be7627db2d8 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/selfdrive/car/hyundai/hyundaicanfd.py @@ -1,4 +1,7 @@ -def create_lkas(packer, enabled, lat_active, apply_steer): +from selfdrive.car.hyundai.values import HyundaiFlags + + +def create_lkas(packer, CP, enabled, lat_active, apply_steer): values = { "LKA_MODE": 2, "LKA_ICON": 2 if enabled else 1, @@ -10,7 +13,9 @@ def create_lkas(packer, enabled, lat_active, apply_steer): "NEW_SIGNAL_1": 0, "NEW_SIGNAL_2": 0, } - return packer.make_can_msg("LKAS", 4, values) + + msg = "LKAS" if CP.flags & HyundaiFlags.CANFD_HDA2 else "LFA" + return packer.make_can_msg(msg, 4, values) def create_cam_0x2a4(packer, camera_values): camera_values.update({ @@ -25,3 +30,17 @@ def create_buttons(packer, cnt, btn): "CRUISE_BUTTONS": btn, } return packer.make_can_msg("CRUISE_BUTTONS", 5, values) + +def create_cruise_info(packer, cruise_info_copy, cancel): + values = cruise_info_copy + if cancel: + values["CRUISE_STATUS"] = 0 + values["CRUISE_INACTIVE"] = 1 + return packer.make_can_msg("CRUISE_INFO", 4, values) + +def create_lfahda_cluster(packer, enabled): + values = { + "HDA_ICON": 1 if enabled else 0, + "LFA_ICON": 2 if enabled else 0, + } + return packer.make_can_msg("LFAHDA_CLUSTER", 4, values) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 6986b973ed97fa..fbf2334980ef44 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -2,7 +2,7 @@ from cereal import car from panda import Panda from common.conversions import Conversions as CV -from selfdrive.car.hyundai.values import CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams +from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR from selfdrive.car import STD_CARGO_KG, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase @@ -160,6 +160,12 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disabl tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.TUCSON_HYBRID_4TH_GEN: + ret.mass = 1680. + STD_CARGO_KG # average of all 3 trims + ret.wheelbase = 2.756 + ret.steerRatio = 16. + tire_stiffness_factor = 0.385 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) # Kia elif candidate == CAR.KIA_SORENTO: @@ -169,7 +175,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disabl ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021): + elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 @@ -177,7 +183,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disabl tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - if candidate == CAR.KIA_NIRO_HEV: + if candidate == CAR.KIA_NIRO_PHEV: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_SELTOS: ret.mass = 1337. + STD_CARGO_KG @@ -284,7 +290,18 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disabl if candidate in CANFD_CAR: ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd)] + + # detect HDA2 with LKAS message + if 0x50 in fingerprint[6]: + ret.flags |= HyundaiFlags.CANFD_HDA2.value + ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 + else: + # non-HDA2 + if 0x1cf not in fingerprint[4]: + ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value else: + ret.enableBsm = 0x58b in fingerprint[0] + 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)] @@ -314,8 +331,6 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[], disabl ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.enableBsm = 0x58b in fingerprint[0] - return ret @staticmethod diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 9db6c3697c4f6f..aa18235223a6eb 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1,3 +1,4 @@ +from enum import IntFlag from dataclasses import dataclass from typing import Dict, List, Optional, Union @@ -29,7 +30,7 @@ def __init__(self, CP): # 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.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.ELANTRA_GT_I30, CAR.IONIQ, - CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_HEV, + CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO, CAR.KIA_STINGER): self.STEER_MAX = 255 @@ -38,6 +39,11 @@ def __init__(self, CP): self.STEER_MAX = 384 +class HyundaiFlags(IntFlag): + CANFD_HDA2 = 1 + CANFD_ALT_BUTTONS = 2 + + class CAR: # Hyundai ELANTRA = "HYUNDAI ELANTRA 2017" @@ -66,12 +72,13 @@ class CAR: VELOSTER = "HYUNDAI VELOSTER 2019" SONATA_HYBRID = "HYUNDAI SONATA HYBRID 2021" IONIQ_5 = "HYUNDAI IONIQ 5 2022" + TUCSON_HYBRID_4TH_GEN = "HYUNDAI TUCSON HYBRID 4TH GEN" # Kia KIA_FORTE = "KIA FORTE E 2018 & GT 2021" KIA_K5_2021 = "KIA K5 2021" KIA_NIRO_EV = "KIA NIRO EV 2020" - KIA_NIRO_HEV = "KIA NIRO HYBRID 2019" + KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019" KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" @@ -128,6 +135,7 @@ class HyundaiCarInfo(CarInfo): CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", "Smart Cruise Control (SCC)", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e), CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a), CAR.IONIQ_5: HyundaiCarInfo("Hyundai Ioniq 5 2022", "Highway Driving Assist II", harness=Harness.hyundai_q), + CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n), # Kia CAR.KIA_FORTE: [ @@ -141,7 +149,7 @@ class HyundaiCarInfo(CarInfo): HyundaiCarInfo("Kia Niro Electric 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), HyundaiCarInfo("Kia Niro Electric 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), ], - CAR.KIA_NIRO_HEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), + CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), CAR.KIA_NIRO_HEV_2021: [ HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h), @@ -695,6 +703,7 @@ class Buttons: (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x81606DE051\x00\x00\x00\x00\x00\x00\x00\x00', @@ -712,6 +721,7 @@ class Buttons: (Ecu.fwdCamera, 0x7c4, None): [ 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', + b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x87VCJLE17622572DK0vd6D\x99\x98y\x97vwVffUfvfC%CuT&Dx\x87o\xff{\x1c\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', @@ -721,6 +731,7 @@ class Buttons: b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', b'\xf1\x87VDKLJ18675252DK6\x89vhgwwwwveVU\x88w\x87w\x99vgf\x97vXfgw_\xff\xc2\xfb\xf1\x89E25\x00\x00\x00\x00\x00\x00\x00\xf1\x82TCK0T33NB2', b'\xf1\x87WAJTE17552812CH4vfFffvfVeT5DwvvVVdFeegeg\x88\x88o\xff\x1a]\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00TCK2T20NB1\x19\xd2\x00\x94', + b'\xf1\x87VDHLG17274082DK2wfFf\x89x\x98wUT5T\x88v\x97xgeGefTGTVvO\xff\x1c\x14\xf1\x81E19\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E19\x00\x00\x00\x00\x00\x00\x00SCK0T33UB2\xee[\x97S', ], }, CAR.PALISADE: { @@ -1039,7 +1050,7 @@ class Buttons: b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', ], }, - CAR.KIA_NIRO_HEV: { + CAR.KIA_NIRO_PHEV: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1292,6 +1303,21 @@ class Buttons: b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', ], }, + CAR.TUCSON_HYBRID_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00NX4 MDPS C 1.00 1.01 56300-P0100 2228', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391312MND0', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00PSBG2441 G19_Rev\x00\x00\x00SNX4T16XXHS01NS2lS\xdfa', + b'\xf1\x8795441-3D220\x00\xf1\x81G19_Rev\x00\x00\x00\xf1\x00PSBG2441 G19_Rev\x00\x00\x00SNX4T16XXHS01NS2lS\xdfa', + ], + }, } CHECKSUM = { @@ -1303,18 +1329,18 @@ class Buttons: # which message has the gear "use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA}, "use_tcu_gears": {CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, - "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022}, + "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022}, # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022}, } -CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5} +CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN} # The camera does SCC on these cars, rather than the radar CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } -HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019} # these cars use a different gas signal +HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019} # these cars use a different gas signal EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022} # these cars require a special panda safety mode due to missing counters and checksums in the messages @@ -1341,7 +1367,7 @@ class Buttons: CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_K5_2021: dbc_dict('hyundai_kia_generic', None), CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), - CAR.KIA_NIRO_HEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), + CAR.KIA_NIRO_PHEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), @@ -1364,5 +1390,6 @@ class Buttons: CAR.KIA_CEED: dbc_dict('hyundai_kia_generic', None), CAR.KIA_EV6: dbc_dict('hyundai_canfd', None), CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), + CAR.TUCSON_HYBRID_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.IONIQ_5: dbc_dict('hyundai_canfd', None), } diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 7e99cccec6f0b6..ed246f15da54db 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -40,7 +40,7 @@ class MazdaCarInfo(CarInfo): CAR.CX9: MazdaCarInfo("Mazda CX-9 2016-20"), CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017-18"), CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017-20"), - CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22"), + CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22", video_link="https://youtu.be/dA3duO4a0O4"), CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"), } diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 5c767ae1a85228..b769cbe5f7086a 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -26,200 +26,201 @@ HYUNDAI.KIA_OPTIMA_H, ] -TestRoute = namedtuple('TestRoute', ['route', 'car_model', 'segment'], defaults=(None,)) +CarTestRoute = namedtuple('CarTestRoute', ['route', 'car_model', 'segment'], defaults=(None,)) routes = [ - TestRoute("efdf9af95e71cd84|2022-05-13--19-03-31", COMMA.BODY), - - TestRoute("0c94aa1e1296d7c6|2021-05-05--19-48-37", CHRYSLER.JEEP_CHEROKEE), - TestRoute("91dfedae61d7bd75|2021-05-22--20-07-52", CHRYSLER.JEEP_CHEROKEE_2019), - TestRoute("420a8e183f1aed48|2020-03-05--07-15-29", CHRYSLER.PACIFICA_2017_HYBRID), - TestRoute("43a685a66291579b|2021-05-27--19-47-29", CHRYSLER.PACIFICA_2018), - TestRoute("378472f830ee7395|2021-05-28--07-38-43", CHRYSLER.PACIFICA_2018_HYBRID), - TestRoute("8190c7275a24557b|2020-01-29--08-33-58", CHRYSLER.PACIFICA_2019_HYBRID), - TestRoute("3d84727705fecd04|2021-05-25--08-38-56", CHRYSLER.PACIFICA_2020), - TestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), - TestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6), + CarTestRoute("efdf9af95e71cd84|2022-05-13--19-03-31", COMMA.BODY), + + CarTestRoute("0c94aa1e1296d7c6|2021-05-05--19-48-37", CHRYSLER.JEEP_CHEROKEE), + CarTestRoute("91dfedae61d7bd75|2021-05-22--20-07-52", CHRYSLER.JEEP_CHEROKEE_2019), + CarTestRoute("420a8e183f1aed48|2020-03-05--07-15-29", CHRYSLER.PACIFICA_2017_HYBRID), + CarTestRoute("43a685a66291579b|2021-05-27--19-47-29", CHRYSLER.PACIFICA_2018), + CarTestRoute("378472f830ee7395|2021-05-28--07-38-43", CHRYSLER.PACIFICA_2018_HYBRID), + CarTestRoute("8190c7275a24557b|2020-01-29--08-33-58", CHRYSLER.PACIFICA_2019_HYBRID), + CarTestRoute("3d84727705fecd04|2021-05-25--08-38-56", CHRYSLER.PACIFICA_2020), + CarTestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), + CarTestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6), #TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION), - TestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA), - TestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL), - TestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), - TestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), - TestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), - - TestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), - TestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.CIVIC), - TestRoute("a859a044a447c2b0|2020-03-03--18-42-45", HONDA.CRV_EU), - TestRoute("68aac44ad69f838e|2021-05-18--20-40-52", HONDA.CRV), - TestRoute("14fed2e5fa0aa1a5|2021-05-25--14-59-42", HONDA.CRV_HYBRID), - TestRoute("52f3e9ae60c0d886|2021-05-23--15-59-43", HONDA.FIT), - TestRoute("2c4292a5cd10536c|2021-08-19--21-32-15", HONDA.FREED), - TestRoute("03be5f2fd5c508d1|2020-04-19--18-44-15", HONDA.HRV), - TestRoute("917b074700869333|2021-05-24--20-40-20", HONDA.ACURA_ILX), - TestRoute("81722949a62ea724|2019-04-06--15-19-25", HONDA.ODYSSEY_CHN), - TestRoute("08a3deb07573f157|2020-03-06--16-11-19", HONDA.ACCORD), # 1.5T - TestRoute("1da5847ac2488106|2021-05-24--19-31-50", HONDA.ACCORD), # 2.0T - TestRoute("085ac1d942c35910|2021-03-25--20-11-15", HONDA.ACCORD), # 2021 with new style HUD msgs - TestRoute("07585b0da3c88459|2021-05-26--18-52-04", HONDA.ACCORDH), - TestRoute("f29e2b57a55e7ad5|2021-03-24--20-52-38", HONDA.ACCORDH), # 2021 with new style HUD msgs - TestRoute("1ad763dd22ef1a0e|2020-02-29--18-37-03", HONDA.CRV_5G), - TestRoute("0a96f86fcfe35964|2020-02-05--07-25-51", HONDA.ODYSSEY), - TestRoute("d83f36766f8012a5|2020-02-05--18-42-21", HONDA.CIVIC_BOSCH_DIESEL), - TestRoute("f0890d16a07a236b|2021-05-25--17-27-22", HONDA.INSIGHT), - TestRoute("07d37d27996096b6|2020-03-04--21-57-27", HONDA.PILOT), - TestRoute("684e8f96bd491a0e|2021-11-03--11-08-42", HONDA.PASSPORT), - TestRoute("0a78dfbacc8504ef|2020-03-04--13-29-55", HONDA.CIVIC_BOSCH), - TestRoute("f34a60d68d83b1e5|2020-10-06--14-35-55", HONDA.ACURA_RDX), - TestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.RIDGELINE), - TestRoute("2d5808fae0b38ac6|2021-09-01--17-14-11", HONDA.HONDA_E), - TestRoute("f44aa96ace22f34a|2021-12-22--06-22-31", HONDA.CIVIC_2022), - - TestRoute("6fe86b4e410e4c37|2020-07-22--16-27-13", HYUNDAI.HYUNDAI_GENESIS), - TestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70), - TestRoute("6b301bf83f10aa90|2020-11-22--16-45-07", HYUNDAI.GENESIS_G80), - TestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.SANTA_FE), - TestRoute("bf43d9df2b660eb0|2021-09-23--14-16-37", HYUNDAI.SANTA_FE_2022), - TestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022), - TestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022), - TestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED), - TestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA), - TestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS), - TestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA), - TestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF), - TestRoute("fb3fd42f0baaa2f8|2022-03-30--15-25-05", HYUNDAI.TUCSON), - TestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO), - TestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE), - TestRoute("22de8111a8c5463c|2022-07-29--13-34-49", HYUNDAI.IONIQ_5), - TestRoute("3f29334d6134fcd4|2022-03-30--22-00-50", HYUNDAI.IONIQ_PHEV_2019), - TestRoute("fa8db5869167f821|2021-06-10--22-50-10", HYUNDAI.IONIQ_PHEV), - TestRoute("2c5cf2dd6102e5da|2020-12-17--16-06-44", HYUNDAI.IONIQ_EV_2020), - TestRoute("610ebb9faaad6b43|2020-06-13--15-28-36", HYUNDAI.IONIQ_EV_LTD), - TestRoute("2c5cf2dd6102e5da|2020-06-26--16-00-08", HYUNDAI.IONIQ), - TestRoute("ab59fe909f626921|2021-10-18--18-34-28", HYUNDAI.IONIQ_HEV_2022), - TestRoute("22d955b2cd499c22|2020-08-10--19-58-21", HYUNDAI.KONA), - TestRoute("efc48acf44b1e64d|2021-05-28--21-05-04", HYUNDAI.KONA_EV), - TestRoute("ff973b941a69366f|2022-07-28--22-01-19", HYUNDAI.KONA_EV_2022, segment=11), - TestRoute("49f3c13141b6bc87|2021-07-28--08-05-13", HYUNDAI.KONA_HEV), - TestRoute("5dddcbca6eb66c62|2020-07-26--13-24-19", HYUNDAI.KIA_STINGER), - TestRoute("d624b3d19adce635|2020-08-01--14-59-12", HYUNDAI.VELOSTER), - TestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), - TestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), - TestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), - TestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_HEV), - TestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021), - TestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE), - TestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA), - TestRoute("82e9cdd3f43bf83e|2021-05-15--02-42-51", HYUNDAI.ELANTRA_2021), - TestRoute("715ac05b594e9c59|2021-06-20--16-21-07", HYUNDAI.ELANTRA_HEV_2021), - TestRoute("7120aa90bbc3add7|2021-08-02--07-12-31", HYUNDAI.SONATA_HYBRID), - TestRoute("715ac05b594e9c59|2021-10-27--23-24-56", HYUNDAI.GENESIS_G70_2020), - - TestRoute("00c829b1b7613dea|2021-06-24--09-10-10", TOYOTA.ALPHARD_TSS2), - TestRoute("912119ebd02c7a42|2022-03-19--07-24-50", TOYOTA.ALPHARDH_TSS2), - TestRoute("000cf3730200c71c|2021-05-24--10-42-05", TOYOTA.AVALON), - TestRoute("0bb588106852abb7|2021-05-26--12-22-01", TOYOTA.AVALON_2019), - TestRoute("87bef2930af86592|2021-05-30--09-40-54", TOYOTA.AVALONH_2019), - TestRoute("e9966711cfb04ce3|2022-01-11--07-59-43", TOYOTA.AVALON_TSS2), - TestRoute("eca1080a91720a54|2022-03-17--13-32-29", TOYOTA.AVALONH_TSS2), - TestRoute("6cdecc4728d4af37|2020-02-23--15-44-18", TOYOTA.CAMRY), - TestRoute("3456ad0cd7281b24|2020-12-13--17-45-56", TOYOTA.CAMRY_TSS2), - TestRoute("ffccc77938ddbc44|2021-01-04--16-55-41", TOYOTA.CAMRYH_TSS2), - TestRoute("54034823d30962f5|2021-05-24--06-37-34", TOYOTA.CAMRYH), - TestRoute("4e45c89c38e8ec4d|2021-05-02--02-49-28", TOYOTA.COROLLA), - TestRoute("5f5afb36036506e4|2019-05-14--02-09-54", TOYOTA.COROLLA_TSS2), - TestRoute("5ceff72287a5c86c|2019-10-19--10-59-02", TOYOTA.COROLLAH_TSS2), - TestRoute("d2525c22173da58b|2021-04-25--16-47-04", TOYOTA.PRIUS), - TestRoute("b14c5b4742e6fc85|2020-07-28--19-50-11", TOYOTA.RAV4), - TestRoute("32a7df20486b0f70|2020-02-06--16-06-50", TOYOTA.RAV4H), - TestRoute("cdf2f7de565d40ae|2019-04-25--03-53-41", TOYOTA.RAV4_TSS2), - TestRoute("a5c341bb250ca2f0|2022-05-18--16-05-17", TOYOTA.RAV4_TSS2_2022), - TestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2), - TestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.RAV4H_TSS2_2022), - TestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), - TestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH), - TestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), - TestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ESH), - TestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), - TestRoute("886fcd8408d570e9|2020-01-29--05-11-22", TOYOTA.LEXUS_RX), - TestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), - TestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RXH), - TestRoute("01b22eb2ed121565|2020-02-02--11-25-51", TOYOTA.LEXUS_RX_TSS2), - TestRoute("b74758c690a49668|2020-05-20--15-58-57", TOYOTA.LEXUS_RXH_TSS2), - TestRoute("ec429c0f37564e3c|2020-02-01--17-28-12", TOYOTA.LEXUS_NXH), - TestRoute("964c09eb11ca8089|2020-11-03--22-04-00", TOYOTA.LEXUS_NX), - TestRoute("3fd5305f8b6ca765|2021-04-28--19-26-49", TOYOTA.LEXUS_NX_TSS2), - TestRoute("09ae96064ed85a14|2022-06-09--12-22-31", TOYOTA.LEXUS_NXH_TSS2), - TestRoute("0a302ffddbb3e3d3|2020-02-08--16-19-08", TOYOTA.HIGHLANDER_TSS2), - TestRoute("437e4d2402abf524|2021-05-25--07-58-50", TOYOTA.HIGHLANDERH_TSS2), - TestRoute("3183cd9b021e89ce|2021-05-25--10-34-44", TOYOTA.HIGHLANDER), - TestRoute("80d16a262e33d57f|2021-05-23--20-01-43", TOYOTA.HIGHLANDERH), - TestRoute("eb6acd681135480d|2019-06-20--20-00-00", TOYOTA.SIENNA), - TestRoute("2e07163a1ba9a780|2019-08-25--13-15-13", TOYOTA.LEXUS_IS), - TestRoute("0a0de17a1e6a2d15|2020-09-21--21-24-41", TOYOTA.PRIUS_TSS2), - TestRoute("9b36accae406390e|2021-03-30--10-41-38", TOYOTA.MIRAI), - TestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.CHR), - TestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.CHRH), - TestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.PRIUS_V), - - TestRoute("202c40641158a6e5|2021-09-21--09-43-24", VOLKSWAGEN.ARTEON_MK1), - TestRoute("2c68dda277d887ac|2021-05-11--15-22-20", VOLKSWAGEN.ATLAS_MK1), - TestRoute("cae14e88932eb364|2021-03-26--14-43-28", VOLKSWAGEN.GOLF_MK7), - TestRoute("58a7d3b707987d65|2021-03-25--17-26-37", VOLKSWAGEN.JETTA_MK7), - TestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.PASSAT_MK8), - TestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.PASSAT_NMS), - TestRoute("0cd0b7f7e31a3853|2021-11-03--19-30-22", VOLKSWAGEN.POLO_MK6), - TestRoute("7d82b2f3a9115f1f|2021-10-21--15-39-42", VOLKSWAGEN.TAOS_MK1), - TestRoute("2744c89a8dda9a51|2021-07-24--21-28-06", VOLKSWAGEN.TCROSS_MK1), - TestRoute("2cef8a0b898f331a|2021-03-25--20-13-57", VOLKSWAGEN.TIGUAN_MK2), - TestRoute("a589dcc642fdb10a|2021-06-14--20-54-26", VOLKSWAGEN.TOURAN_MK2), - TestRoute("a459f4556782eba1|2021-09-19--09-48-00", VOLKSWAGEN.TRANSPORTER_T61), - TestRoute("0cd0b7f7e31a3853|2021-11-18--00-38-32", VOLKSWAGEN.TROC_MK1), - TestRoute("07667b885add75fd|2021-01-23--19-48-42", VOLKSWAGEN.AUDI_A3_MK3), - TestRoute("6c6b466346192818|2021-06-06--14-17-47", VOLKSWAGEN.AUDI_Q2_MK1), - TestRoute("0cd0b7f7e31a3853|2021-12-03--03-12-05", VOLKSWAGEN.AUDI_Q3_MK2), - TestRoute("8f205bdd11bcbb65|2021-03-26--01-00-17", VOLKSWAGEN.SEAT_ATECA_MK1), - TestRoute("fc6b6c9a3471c846|2021-05-27--13-39-56", VOLKSWAGEN.SEAT_LEON_MK3), - TestRoute("12d6ae3057c04b0d|2021-09-15--00-04-07", VOLKSWAGEN.SKODA_KAMIQ_MK1), - TestRoute("12d6ae3057c04b0d|2021-09-04--21-21-21", VOLKSWAGEN.SKODA_KAROQ_MK1), - TestRoute("90434ff5d7c8d603|2021-03-15--12-07-31", VOLKSWAGEN.SKODA_KODIAQ_MK1), - TestRoute("66e5edc3a16459c5|2021-05-25--19-00-29", VOLKSWAGEN.SKODA_OCTAVIA_MK3), - TestRoute("026b6d18fba6417f|2021-03-26--09-17-04", VOLKSWAGEN.SKODA_SCALA_MK1), - TestRoute("b2e9858e29db492b|2021-03-26--16-58-42", VOLKSWAGEN.SKODA_SUPERB_MK3), - - TestRoute("3c8f0c502e119c1c|2020-06-30--12-58-02", SUBARU.ASCENT), - TestRoute("c321c6b697c5a5ff|2020-06-23--11-04-33", SUBARU.FORESTER), - TestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA), - TestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020), - TestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=3), - TestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3), + CarTestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA), + CarTestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL), + CarTestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), + CarTestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), + CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), + CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), + + CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), + CarTestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.CIVIC), + CarTestRoute("a859a044a447c2b0|2020-03-03--18-42-45", HONDA.CRV_EU), + CarTestRoute("68aac44ad69f838e|2021-05-18--20-40-52", HONDA.CRV), + CarTestRoute("14fed2e5fa0aa1a5|2021-05-25--14-59-42", HONDA.CRV_HYBRID), + CarTestRoute("52f3e9ae60c0d886|2021-05-23--15-59-43", HONDA.FIT), + CarTestRoute("2c4292a5cd10536c|2021-08-19--21-32-15", HONDA.FREED), + CarTestRoute("03be5f2fd5c508d1|2020-04-19--18-44-15", HONDA.HRV), + CarTestRoute("917b074700869333|2021-05-24--20-40-20", HONDA.ACURA_ILX), + CarTestRoute("81722949a62ea724|2019-04-06--15-19-25", HONDA.ODYSSEY_CHN), + CarTestRoute("08a3deb07573f157|2020-03-06--16-11-19", HONDA.ACCORD), # 1.5T + CarTestRoute("1da5847ac2488106|2021-05-24--19-31-50", HONDA.ACCORD), # 2.0T + CarTestRoute("085ac1d942c35910|2021-03-25--20-11-15", HONDA.ACCORD), # 2021 with new style HUD msgs + CarTestRoute("07585b0da3c88459|2021-05-26--18-52-04", HONDA.ACCORDH), + CarTestRoute("f29e2b57a55e7ad5|2021-03-24--20-52-38", HONDA.ACCORDH), # 2021 with new style HUD msgs + CarTestRoute("1ad763dd22ef1a0e|2020-02-29--18-37-03", HONDA.CRV_5G), + CarTestRoute("0a96f86fcfe35964|2020-02-05--07-25-51", HONDA.ODYSSEY), + CarTestRoute("d83f36766f8012a5|2020-02-05--18-42-21", HONDA.CIVIC_BOSCH_DIESEL), + CarTestRoute("f0890d16a07a236b|2021-05-25--17-27-22", HONDA.INSIGHT), + CarTestRoute("07d37d27996096b6|2020-03-04--21-57-27", HONDA.PILOT), + CarTestRoute("684e8f96bd491a0e|2021-11-03--11-08-42", HONDA.PASSPORT), + CarTestRoute("0a78dfbacc8504ef|2020-03-04--13-29-55", HONDA.CIVIC_BOSCH), + CarTestRoute("f34a60d68d83b1e5|2020-10-06--14-35-55", HONDA.ACURA_RDX), + CarTestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.RIDGELINE), + CarTestRoute("2d5808fae0b38ac6|2021-09-01--17-14-11", HONDA.HONDA_E), + CarTestRoute("f44aa96ace22f34a|2021-12-22--06-22-31", HONDA.CIVIC_2022), + + CarTestRoute("6fe86b4e410e4c37|2020-07-22--16-27-13", HYUNDAI.HYUNDAI_GENESIS), + CarTestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70), + CarTestRoute("6b301bf83f10aa90|2020-11-22--16-45-07", HYUNDAI.GENESIS_G80), + CarTestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.SANTA_FE), + CarTestRoute("bf43d9df2b660eb0|2021-09-23--14-16-37", HYUNDAI.SANTA_FE_2022), + CarTestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022), + CarTestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022, segment=1), + CarTestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED), + CarTestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA), + CarTestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS), + CarTestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA), + CarTestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF), + CarTestRoute("fb3fd42f0baaa2f8|2022-03-30--15-25-05", HYUNDAI.TUCSON), + CarTestRoute("36e10531feea61a4|2022-07-25--13-37-42", HYUNDAI.TUCSON_HYBRID_4TH_GEN), + CarTestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO), + CarTestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE), + CarTestRoute("22de8111a8c5463c|2022-07-29--13-34-49", HYUNDAI.IONIQ_5), + CarTestRoute("3f29334d6134fcd4|2022-03-30--22-00-50", HYUNDAI.IONIQ_PHEV_2019), + CarTestRoute("fa8db5869167f821|2021-06-10--22-50-10", HYUNDAI.IONIQ_PHEV), + CarTestRoute("2c5cf2dd6102e5da|2020-12-17--16-06-44", HYUNDAI.IONIQ_EV_2020), + CarTestRoute("610ebb9faaad6b43|2020-06-13--15-28-36", HYUNDAI.IONIQ_EV_LTD), + CarTestRoute("2c5cf2dd6102e5da|2020-06-26--16-00-08", HYUNDAI.IONIQ), + CarTestRoute("ab59fe909f626921|2021-10-18--18-34-28", HYUNDAI.IONIQ_HEV_2022), + CarTestRoute("22d955b2cd499c22|2020-08-10--19-58-21", HYUNDAI.KONA), + CarTestRoute("efc48acf44b1e64d|2021-05-28--21-05-04", HYUNDAI.KONA_EV), + CarTestRoute("ff973b941a69366f|2022-07-28--22-01-19", HYUNDAI.KONA_EV_2022, segment=11), + CarTestRoute("49f3c13141b6bc87|2021-07-28--08-05-13", HYUNDAI.KONA_HEV), + CarTestRoute("5dddcbca6eb66c62|2020-07-26--13-24-19", HYUNDAI.KIA_STINGER), + CarTestRoute("d624b3d19adce635|2020-08-01--14-59-12", HYUNDAI.VELOSTER), + CarTestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), + CarTestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), + CarTestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), + CarTestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_PHEV), + CarTestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021), + CarTestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE), + CarTestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA), + CarTestRoute("82e9cdd3f43bf83e|2021-05-15--02-42-51", HYUNDAI.ELANTRA_2021), + CarTestRoute("715ac05b594e9c59|2021-06-20--16-21-07", HYUNDAI.ELANTRA_HEV_2021), + CarTestRoute("7120aa90bbc3add7|2021-08-02--07-12-31", HYUNDAI.SONATA_HYBRID), + CarTestRoute("715ac05b594e9c59|2021-10-27--23-24-56", HYUNDAI.GENESIS_G70_2020), + + CarTestRoute("00c829b1b7613dea|2021-06-24--09-10-10", TOYOTA.ALPHARD_TSS2), + CarTestRoute("912119ebd02c7a42|2022-03-19--07-24-50", TOYOTA.ALPHARDH_TSS2), + CarTestRoute("000cf3730200c71c|2021-05-24--10-42-05", TOYOTA.AVALON), + CarTestRoute("0bb588106852abb7|2021-05-26--12-22-01", TOYOTA.AVALON_2019), + CarTestRoute("87bef2930af86592|2021-05-30--09-40-54", TOYOTA.AVALONH_2019), + CarTestRoute("e9966711cfb04ce3|2022-01-11--07-59-43", TOYOTA.AVALON_TSS2), + CarTestRoute("eca1080a91720a54|2022-03-17--13-32-29", TOYOTA.AVALONH_TSS2), + CarTestRoute("6cdecc4728d4af37|2020-02-23--15-44-18", TOYOTA.CAMRY), + CarTestRoute("3456ad0cd7281b24|2020-12-13--17-45-56", TOYOTA.CAMRY_TSS2), + CarTestRoute("ffccc77938ddbc44|2021-01-04--16-55-41", TOYOTA.CAMRYH_TSS2), + CarTestRoute("54034823d30962f5|2021-05-24--06-37-34", TOYOTA.CAMRYH), + CarTestRoute("4e45c89c38e8ec4d|2021-05-02--02-49-28", TOYOTA.COROLLA), + CarTestRoute("5f5afb36036506e4|2019-05-14--02-09-54", TOYOTA.COROLLA_TSS2), + CarTestRoute("5ceff72287a5c86c|2019-10-19--10-59-02", TOYOTA.COROLLAH_TSS2), + CarTestRoute("d2525c22173da58b|2021-04-25--16-47-04", TOYOTA.PRIUS), + CarTestRoute("b14c5b4742e6fc85|2020-07-28--19-50-11", TOYOTA.RAV4), + CarTestRoute("32a7df20486b0f70|2020-02-06--16-06-50", TOYOTA.RAV4H), + CarTestRoute("cdf2f7de565d40ae|2019-04-25--03-53-41", TOYOTA.RAV4_TSS2), + CarTestRoute("a5c341bb250ca2f0|2022-05-18--16-05-17", TOYOTA.RAV4_TSS2_2022), + CarTestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2), + CarTestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.RAV4H_TSS2_2022), + CarTestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), + CarTestRoute("da23c367491f53e2|2021-05-21--09-09-11", TOYOTA.LEXUS_CTH, segment=3), + CarTestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), + CarTestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ESH), + CarTestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), + CarTestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), + CarTestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RXH), + CarTestRoute("01b22eb2ed121565|2020-02-02--11-25-51", TOYOTA.LEXUS_RX_TSS2), + CarTestRoute("b74758c690a49668|2020-05-20--15-58-57", TOYOTA.LEXUS_RXH_TSS2), + CarTestRoute("ec429c0f37564e3c|2020-02-01--17-28-12", TOYOTA.LEXUS_NXH), + CarTestRoute("964c09eb11ca8089|2020-11-03--22-04-00", TOYOTA.LEXUS_NX), + CarTestRoute("3fd5305f8b6ca765|2021-04-28--19-26-49", TOYOTA.LEXUS_NX_TSS2), + CarTestRoute("09ae96064ed85a14|2022-06-09--12-22-31", TOYOTA.LEXUS_NXH_TSS2), + CarTestRoute("0a302ffddbb3e3d3|2020-02-08--16-19-08", TOYOTA.HIGHLANDER_TSS2), + CarTestRoute("437e4d2402abf524|2021-05-25--07-58-50", TOYOTA.HIGHLANDERH_TSS2), + CarTestRoute("3183cd9b021e89ce|2021-05-25--10-34-44", TOYOTA.HIGHLANDER), + CarTestRoute("80d16a262e33d57f|2021-05-23--20-01-43", TOYOTA.HIGHLANDERH), + CarTestRoute("eb6acd681135480d|2019-06-20--20-00-00", TOYOTA.SIENNA), + CarTestRoute("2e07163a1ba9a780|2019-08-25--13-15-13", TOYOTA.LEXUS_IS), + CarTestRoute("0a0de17a1e6a2d15|2020-09-21--21-24-41", TOYOTA.PRIUS_TSS2), + CarTestRoute("9b36accae406390e|2021-03-30--10-41-38", TOYOTA.MIRAI), + CarTestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.CHR), + CarTestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.CHRH), + CarTestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.PRIUS_V), + + CarTestRoute("202c40641158a6e5|2021-09-21--09-43-24", VOLKSWAGEN.ARTEON_MK1), + CarTestRoute("2c68dda277d887ac|2021-05-11--15-22-20", VOLKSWAGEN.ATLAS_MK1), + CarTestRoute("cae14e88932eb364|2021-03-26--14-43-28", VOLKSWAGEN.GOLF_MK7), + CarTestRoute("58a7d3b707987d65|2021-03-25--17-26-37", VOLKSWAGEN.JETTA_MK7), + CarTestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.PASSAT_MK8), + CarTestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.PASSAT_NMS), + CarTestRoute("0cd0b7f7e31a3853|2021-11-03--19-30-22", VOLKSWAGEN.POLO_MK6), + CarTestRoute("7d82b2f3a9115f1f|2021-10-21--15-39-42", VOLKSWAGEN.TAOS_MK1), + CarTestRoute("2744c89a8dda9a51|2021-07-24--21-28-06", VOLKSWAGEN.TCROSS_MK1), + CarTestRoute("2cef8a0b898f331a|2021-03-25--20-13-57", VOLKSWAGEN.TIGUAN_MK2), + CarTestRoute("a589dcc642fdb10a|2021-06-14--20-54-26", VOLKSWAGEN.TOURAN_MK2), + CarTestRoute("a459f4556782eba1|2021-09-19--09-48-00", VOLKSWAGEN.TRANSPORTER_T61), + CarTestRoute("0cd0b7f7e31a3853|2021-11-18--00-38-32", VOLKSWAGEN.TROC_MK1), + CarTestRoute("07667b885add75fd|2021-01-23--19-48-42", VOLKSWAGEN.AUDI_A3_MK3), + CarTestRoute("6c6b466346192818|2021-06-06--14-17-47", VOLKSWAGEN.AUDI_Q2_MK1), + CarTestRoute("0cd0b7f7e31a3853|2021-12-03--03-12-05", VOLKSWAGEN.AUDI_Q3_MK2), + CarTestRoute("8f205bdd11bcbb65|2021-03-26--01-00-17", VOLKSWAGEN.SEAT_ATECA_MK1), + CarTestRoute("fc6b6c9a3471c846|2021-05-27--13-39-56", VOLKSWAGEN.SEAT_LEON_MK3), + CarTestRoute("12d6ae3057c04b0d|2021-09-15--00-04-07", VOLKSWAGEN.SKODA_KAMIQ_MK1), + CarTestRoute("12d6ae3057c04b0d|2021-09-04--21-21-21", VOLKSWAGEN.SKODA_KAROQ_MK1), + CarTestRoute("90434ff5d7c8d603|2021-03-15--12-07-31", VOLKSWAGEN.SKODA_KODIAQ_MK1), + CarTestRoute("66e5edc3a16459c5|2021-05-25--19-00-29", VOLKSWAGEN.SKODA_OCTAVIA_MK3), + CarTestRoute("026b6d18fba6417f|2021-03-26--09-17-04", VOLKSWAGEN.SKODA_SCALA_MK1), + CarTestRoute("b2e9858e29db492b|2021-03-26--16-58-42", VOLKSWAGEN.SKODA_SUPERB_MK3), + + CarTestRoute("3c8f0c502e119c1c|2020-06-30--12-58-02", SUBARU.ASCENT), + CarTestRoute("c321c6b697c5a5ff|2020-06-23--11-04-33", SUBARU.FORESTER), + CarTestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA), + CarTestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020), + CarTestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=3), + CarTestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3), # Pre-global, dashcam - TestRoute("95441c38ae8c130e|2020-06-08--12-10-17", SUBARU.FORESTER_PREGLOBAL), - TestRoute("df5ca7660000fba8|2020-06-16--17-37-19", SUBARU.LEGACY_PREGLOBAL), - TestRoute("5ab784f361e19b78|2020-06-08--16-30-41", SUBARU.OUTBACK_PREGLOBAL), - TestRoute("e19eb5d5353b1ac1|2020-08-09--14-37-56", SUBARU.OUTBACK_PREGLOBAL_2018), - - TestRoute("fbbfa6af821552b9|2020-03-03--08-09-43", NISSAN.XTRAIL), - TestRoute("5b7c365c50084530|2020-03-25--22-10-13", NISSAN.LEAF), - TestRoute("22c3dcce2dd627eb|2020-12-30--16-38-48", NISSAN.LEAF_IC), - TestRoute("059ab9162e23198e|2020-05-30--09-41-01", NISSAN.ROGUE), - TestRoute("b72d3ec617c0a90f|2020-12-11--15-38-17", NISSAN.ALTIMA), - - TestRoute("32a319f057902bb3|2020-04-27--15-18-58", MAZDA.CX5), - TestRoute("10b5a4b380434151|2020-08-26--17-11-45", MAZDA.CX9), - TestRoute("74f1038827005090|2020-08-26--20-05-50", MAZDA.MAZDA3), - TestRoute("fb53c640f499b73d|2021-06-01--04-17-56", MAZDA.MAZDA6), - TestRoute("f6d5b1a9d7a1c92e|2021-07-08--06-56-59", MAZDA.CX9_2021), - TestRoute("a4af1602d8e668ac|2022-02-03--12-17-07", MAZDA.CX5_2022), - - TestRoute("6c14ee12b74823ce|2021-06-30--11-49-02", TESLA.AP1_MODELS), - TestRoute("bb50caf5f0945ab1|2021-06-19--17-20-18", TESLA.AP2_MODELS), + CarTestRoute("95441c38ae8c130e|2020-06-08--12-10-17", SUBARU.FORESTER_PREGLOBAL), + CarTestRoute("df5ca7660000fba8|2020-06-16--17-37-19", SUBARU.LEGACY_PREGLOBAL), + CarTestRoute("5ab784f361e19b78|2020-06-08--16-30-41", SUBARU.OUTBACK_PREGLOBAL), + CarTestRoute("e19eb5d5353b1ac1|2020-08-09--14-37-56", SUBARU.OUTBACK_PREGLOBAL_2018), + + CarTestRoute("fbbfa6af821552b9|2020-03-03--08-09-43", NISSAN.XTRAIL), + CarTestRoute("5b7c365c50084530|2020-03-25--22-10-13", NISSAN.LEAF), + CarTestRoute("22c3dcce2dd627eb|2020-12-30--16-38-48", NISSAN.LEAF_IC), + CarTestRoute("059ab9162e23198e|2020-05-30--09-41-01", NISSAN.ROGUE), + CarTestRoute("b72d3ec617c0a90f|2020-12-11--15-38-17", NISSAN.ALTIMA), + + CarTestRoute("32a319f057902bb3|2020-04-27--15-18-58", MAZDA.CX5), + CarTestRoute("10b5a4b380434151|2020-08-26--17-11-45", MAZDA.CX9), + CarTestRoute("74f1038827005090|2020-08-26--20-05-50", MAZDA.MAZDA3), + CarTestRoute("fb53c640f499b73d|2021-06-01--04-17-56", MAZDA.MAZDA6), + CarTestRoute("f6d5b1a9d7a1c92e|2021-07-08--06-56-59", MAZDA.CX9_2021), + CarTestRoute("a4af1602d8e668ac|2022-02-03--12-17-07", MAZDA.CX5_2022), + + CarTestRoute("6c14ee12b74823ce|2021-06-30--11-49-02", TESLA.AP1_MODELS), + CarTestRoute("bb50caf5f0945ab1|2021-06-19--17-20-18", TESLA.AP2_MODELS), # Segments that test specific issues # Controls mismatch due to interceptor threshold - TestRoute("cfb32f0fb91b173b|2022-04-06--14-54-45", HONDA.CIVIC, segment=21), - TestRoute("5a8762b91fc70467|2022-04-14--21-26-20", TOYOTA.RAV4, segment=2), + CarTestRoute("cfb32f0fb91b173b|2022-04-06--14-54-45", HONDA.CIVIC, segment=21), + CarTestRoute("5a8762b91fc70467|2022-04-14--21-26-20", TOYOTA.RAV4, segment=2), # Controls mismatch due to standstill threshold - TestRoute("bec2dcfde6a64235|2022-04-08--14-21-32", HONDA.CRV_HYBRID, segment=22), + CarTestRoute("bec2dcfde6a64235|2022-04-08--14-21-32", HONDA.CRV_HYBRID, segment=22), ] diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 4a1f1a61ee46fa..502df3fe3f1524 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -15,7 +15,7 @@ from selfdrive.car.gm.values import CAR as GM from selfdrive.car.honda.values import CAR as HONDA, HONDA_BOSCH from selfdrive.car.hyundai.values import CAR as HYUNDAI -from selfdrive.car.tests.routes import non_tested_cars, routes, TestRoute +from selfdrive.car.tests.routes import non_tested_cars, routes, CarTestRoute from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader from tools.lib.route import Route @@ -38,7 +38,7 @@ for r in routes: routes_by_car[r.car_model].add(r) -test_cases: List[Tuple[str, Optional[TestRoute]]] = [] +test_cases: List[Tuple[str, Optional[CarTestRoute]]] = [] for i, c in enumerate(sorted(all_known_cars())): if i % NUM_JOBS == JOB_ID: test_cases.extend((c, r) for r in routes_by_car.get(c, (None, ))) @@ -81,6 +81,7 @@ def setUpClass(cls): except Exception: continue + car_fw = [] can_msgs = [] fingerprint = defaultdict(dict) for msg in lr: @@ -90,6 +91,7 @@ def setUpClass(cls): fingerprint[m.src][m.address] = len(m.dat) can_msgs.append(msg) elif msg.which() == "carParams": + car_fw = msg.carParams.carFw if msg.carParams.openpilotLongitudinalControl: disable_radar = True if cls.car_model is None and not cls.ci: @@ -103,7 +105,7 @@ def setUpClass(cls): cls.can_msgs = sorted(can_msgs, key=lambda msg: msg.logMonoTime) cls.CarInterface, cls.CarController, cls.CarState = interfaces[cls.car_model] - cls.CP = cls.CarInterface.get_params(cls.car_model, fingerprint, [], disable_radar) + cls.CP = cls.CarInterface.get_params(cls.car_model, fingerprint, car_fw, disable_radar) assert cls.CP assert cls.CP.carFingerprint == cls.car_model @@ -138,19 +140,23 @@ def test_car_params(self): raise Exception("unkown tuning") def test_car_interface(self): - # TODO: also check for checkusm and counter violations from can parser + # TODO: also check for checksum violations from can parser can_invalid_cnt = 0 + can_valid = False CC = car.CarControl.new_message() for i, msg in enumerate(self.can_msgs): CS = self.CI.update(CC, (msg.as_builder().to_bytes(),)) self.CI.apply(CC) - # wait 2s for low frequency msgs to be seen - if i > 200: + if CS.canValid: + can_valid = True + + # wait max of 2s for low frequency msgs to be seen + if i > 200 or can_valid: can_invalid_cnt += not CS.canValid - self.assertLess(can_invalid_cnt, 50) + self.assertEqual(can_invalid_cnt, 0) def test_radar_interface(self): os.environ['NO_RADAR_SLEEP'] = "1" diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 8dd8c43220d097..14ee7e223962f8 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -25,7 +25,9 @@ RAM 1500 5TH GEN: [2.0, 2.0, 0.0] RAM HD 5TH GEN: [1.4, 1.4, 0.0] SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] +CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] +HYUNDAI TUCSON HYBRID 4TH GEN: [2.5, 2.5, 0.0] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 537915919c39eb..843e7806dc9bba 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -94,12 +94,11 @@ def update(self, cp, cp_cam): ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS - if self.CP.carFingerprint in RADAR_ACC_CAR: - self.acc_type = cp.vl["ACC_CONTROL"]["ACC_TYPE"] - ret.stockFcw = bool(cp.vl["ACC_HUD"]["FCW"]) - elif self.CP.carFingerprint in TSS2_CAR: - self.acc_type = cp_cam.vl["ACC_CONTROL"]["ACC_TYPE"] - ret.stockFcw = bool(cp_cam.vl["ACC_HUD"]["FCW"]) + cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp + + if self.CP.carFingerprint in (TSS2_CAR | RADAR_ACC_CAR): + self.acc_type = cp_acc.vl["ACC_CONTROL"]["ACC_TYPE"] + ret.stockFcw = bool(cp_acc.vl["ACC_HUD"]["FCW"]) # some TSS2 cars have low speed lockout permanently set, so ignore on those cars # these cars are identified by an ACC_TYPE value of 2. @@ -120,10 +119,11 @@ def update(self, cp, cp_cam): ret.cruiseState.nonAdaptive = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] in (1, 2, 3, 4, 5, 6) ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) - ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5) - ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 + if not self.CP.enableDsu: + ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) + if self.CP.enableBsm: ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1) @@ -219,25 +219,31 @@ def get_can_parser(CP): ("ACC_HUD", 1), ] + if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu: + signals += [ + ("FORCE", "PRE_COLLISION"), + ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), + ] + checks += [ + ("PRE_COLLISION", 33), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): - signals = [ - ("FORCE", "PRE_COLLISION"), - ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), - ] - - checks = [ - ("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent - ] + signals = [] + checks = [] if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): signals += [ + ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), + ("FORCE", "PRE_COLLISION"), ("ACC_TYPE", "ACC_CONTROL"), ("FCW", "ACC_HUD"), ] checks += [ + ("PRE_COLLISION", 33), ("ACC_CONTROL", 33), ("ACC_HUD", 1), ] diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 8915146063de3f..7b4031ca64ebcc 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -783,6 +783,7 @@ class ToyotaCarInfo(CarInfo): b'\x01896637626000\x00\x00\x00\x00', b'\x01896637648000\x00\x00\x00\x00', b'\x01896637643000\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'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', @@ -827,6 +828,7 @@ class ToyotaCarInfo(CarInfo): 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'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', diff --git a/selfdrive/debug/test_car_model.py b/selfdrive/debug/test_car_model.py index 9082dbe3d6b4e2..4de5b267628810 100755 --- a/selfdrive/debug/test_car_model.py +++ b/selfdrive/debug/test_car_model.py @@ -4,11 +4,11 @@ from typing import List, Tuple import unittest -from selfdrive.car.tests.routes import TestRoute +from selfdrive.car.tests.routes import CarTestRoute from selfdrive.car.tests.test_models import TestCarModel -def create_test_models_suite(routes: List[Tuple[str, TestRoute]], ci=False) -> unittest.TestSuite: +def create_test_models_suite(routes: List[Tuple[str, CarTestRoute]], ci=False) -> unittest.TestSuite: test_suite = unittest.TestSuite() for car_model, test_route in routes: # create new test case and discover tests @@ -30,7 +30,7 @@ def create_test_models_suite(routes: List[Tuple[str, TestRoute]], ci=False) -> u parser.print_help() sys.exit() - test_route = TestRoute(args.route, args.car, segment=args.segment) + test_route = CarTestRoute(args.route, args.car, segment=args.segment) test_suite = create_test_models_suite([(args.car, test_route)], ci=args.ci) unittest.TextTestRunner().run(test_suite) diff --git a/selfdrive/loggerd/encoder/v4l_encoder.cc b/selfdrive/loggerd/encoder/v4l_encoder.cc index b3bd692b1639bd..016e6c57063f73 100644 --- a/selfdrive/loggerd/encoder/v4l_encoder.cc +++ b/selfdrive/loggerd/encoder/v4l_encoder.cc @@ -303,4 +303,10 @@ V4LEncoder::~V4LEncoder() { checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, 0); close(fd); + + for (int i = 0; i < BUF_OUT_COUNT; i++) { + if (buf_out[i].free() != 0) { + LOGE("Failed to free buffer"); + } + } } diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b9e99cd61754bb..f77f244594f725 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -93a136f91739847afe1e1a4a1e98bc7c0adb5ec8 +656daeb9de3680258527500ecae4ddff323b2e59 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 2a005cf4cc67d8..e8c2e1dc9494e6 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -18,7 +18,7 @@ original_segments = [ ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY ("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA - ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), # HYUNDAI.KIA_EV6 + ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), # HYUNDAI.KIA_EV6 ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI) ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR) ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 @@ -40,7 +40,7 @@ segments = [ ("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"), ("HYUNDAI", "regen114E5FF24D8|2022-07-14--17-08-47--0"), - ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), + ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), ("TOYOTA", "regenBA97410FBEC|2022-07-06--14-26-49--0"), ("TOYOTA2", "regenDEDB1D9C991|2022-07-06--14-54-08--0"), ("TOYOTA3", "regenDDC1FE60734|2022-07-06--14-32-06--0"), diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 31651706c698a5..93598a1b066c4f 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -37,7 +37,7 @@ "selfdrive.thermald.thermald": 3.87, "selfdrive.locationd.calibrationd": 2.0, "./_soundd": 1.0, - "selfdrive.monitoring.dmonitoringd": 1.90, + "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 1.54, "system.logmessaged": 0.2, "./clocksd": 0.02, diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index accab67bf071eb..a84542d29107b6 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -33,7 +33,7 @@ void Sidebar::drawMetric(QPainter &p, const QPair &label, QCol } Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { - home_img = loadPixmap("../assets/images/button_home.png", {180, 180}); + home_img = loadPixmap("../assets/images/button_home.png", home_btn.size()); settings_img = loadPixmap("../assets/images/button_settings.png", settings_btn.size(), Qt::IgnoreAspectRatio); connect(this, &Sidebar::valueChanged, [=] { update(); }); @@ -43,9 +43,16 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { setFixedWidth(300); QObject::connect(uiState(), &UIState::uiUpdate, this, &Sidebar::updateState); + + pm = std::make_unique>({"userFlag"}); } void Sidebar::mouseReleaseEvent(QMouseEvent *event) { + if (home_btn.contains(event->pos())) { + MessageBuilder msg; + msg.initEvent().initUserFlag(); + pm->send("userFlag", msg); + } if (settings_btn.contains(event->pos())) { emit openSettings(); } @@ -99,7 +106,7 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.setOpacity(0.65); p.drawPixmap(settings_btn.x(), settings_btn.y(), settings_img); p.setOpacity(1.0); - p.drawPixmap(60, 1080 - 180 - 40, home_img); + p.drawPixmap(home_btn.x(), home_btn.y(), home_img); // network int x = 58; diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 4c6d8f47e5bc35..0140673aac3fb1 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -43,6 +43,7 @@ public slots: {cereal::DeviceState::NetworkType::CELL5_G, tr("5G")} }; + const QRect home_btn = QRect(60, 860, 180, 180); const QRect settings_btn = QRect(50, 35, 200, 117); const QColor good_color = QColor(255, 255, 255); const QColor warning_color = QColor(218, 202, 37); @@ -52,4 +53,7 @@ public slots: ItemStatus connect_status, panda_status, temp_status; QString net_type; int net_strength = 0; + +private: + std::unique_ptr pm; }; diff --git a/selfdrive/ui/translations/README.md b/selfdrive/ui/translations/README.md index 5d469861482bb3..ac3112c61af3fb 100644 --- a/selfdrive/ui/translations/README.md +++ b/selfdrive/ui/translations/README.md @@ -1,11 +1,6 @@ # Multilanguage -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_en.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_en.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_pt.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_pt.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_zh-CHT.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_zh-CHT.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_zh-CHS.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_zh-CHS.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_ko.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_ko.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_ja.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_ja.ts) +[![languages](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge.svg)](#) ## Contributing diff --git a/selfdrive/ui/translations/create_badges.py b/selfdrive/ui/translations/create_badges.py index d9e2d443b969d4..451fbb23eb12b3 100755 --- a/selfdrive/ui/translations/create_badges.py +++ b/selfdrive/ui/translations/create_badges.py @@ -8,20 +8,17 @@ TRANSLATION_TAG = "'] + for idx, (name, file) in enumerate(translation_files.items()): with open(os.path.join(TRANSLATIONS_DIR, f"{file}.ts"), "r") as tr_f: tr_file = tr_f.read() - print(f"[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/{TRANSLATION_BADGE.format(file)})]({TRANSLATION_LINK.format(file)}.ts)") - total_translations = 0 unfinished_translations = 0 for line in tr_file.splitlines(): @@ -35,6 +32,16 @@ r = requests.get(f"https://img.shields.io/badge/LANGUAGE {name}-{percent_finished}%25 complete-{color}") assert r.status_code == 200, "Error downloading badge" + content_svg = r.content.decode("utf-8") + + # make tag ids in each badge unique + for tag in ("r", "s"): + content_svg = content_svg.replace(f'id="{tag}"', f'id="{tag}{idx}"') + content_svg = content_svg.replace(f'"url(#{tag})"', f'"url(#{tag}{idx})"') + + badge_svg.extend([f'', content_svg, ""]) + + badge_svg.append("") - with open(os.path.join(BASEDIR, TRANSLATION_BADGE.format(file)), "wb") as badge_f: - badge_f.write(r.content) + with open(os.path.join(BASEDIR, "translation_badge.svg"), "w") as badge_f: + badge_f.write("\n".join(badge_svg)) diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index b66bc4b80d6660..dd9f933dcf75ff 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 接続 - + OFFLINE オフライン - - + + ONLINE オンライン - + ERROR エラー - - - + + + TEMP 温度 - + HIGH 高温 - + GOOD 最適 - + OK OK - + VEHICLE 車両 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 検索 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index a67b957e832534..d4abe861962c3a 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 연결 - + OFFLINE 오프라인 - - + + ONLINE 온라인 - + ERROR 오류 - - - + + + TEMP 온도 - + HIGH 높음 - + GOOD 좋음 - + OK 경고 - + VEHICLE 차량 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 검색중 diff --git a/selfdrive/ui/translations/main_pt.ts b/selfdrive/ui/translations/main_pt.ts index 912afa38a43c10..3d5eda118ce042 100644 --- a/selfdrive/ui/translations/main_pt.ts +++ b/selfdrive/ui/translations/main_pt.ts @@ -880,71 +880,71 @@ trabalho definido Sidebar - - + + CONNECT CONEXÃO - + OFFLINE DESCONEC - - + + ONLINE CONECTADO - + ERROR ERRO - - - + + + TEMP TEMP - + HIGH ALTA - + GOOD BOA - + OK OK - + VEHICLE VEÍCULO - + NO SEM - + PANDA PANDA - + GPS GPS - + SEARCH PROCURA diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts new file mode 100644 index 00000000000000..3277f537404ff0 --- /dev/null +++ b/selfdrive/ui/translations/main_th.ts @@ -0,0 +1,1303 @@ + + + + + AbstractAlert + + + Close + ปิด + + + + Snooze Update + เลื่อนการอัปเดต + + + + Reboot and Update + รีบูตและอัปเดต + + + + AdvancedNetworking + + + Back + ย้อนกลับ + + + + Enable Tethering + ปล่อยฮอตสปอต + + + + Tethering Password + รหัสผ่านฮอตสปอต + + + + + EDIT + แก้ไข + + + + Enter new tethering password + ป้อนรหัสผ่านฮอตสปอตใหม่ + + + + IP Address + หมายเลขไอพี + + + + Enable Roaming + เปิดใช้งานโรมมิ่ง + + + + APN Setting + ตั้งค่า APN + + + + Enter APN + ป้อนค่า APN + + + + leave blank for automatic configuration + เว้นว่างเพื่อตั้งค่าอัตโนมัติ + + + + ConfirmationDialog + + + + Ok + ตกลง + + + + Cancel + ยกเลิก + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + คุณต้องยอมรับเงื่อนไขและข้อตกลง เพื่อใช้งาน openpilot + + + + Back + ย้อนกลับ + + + + Decline, uninstall %1 + ปฏิเสธ และถอนการติดตั้ง %1 + + + + DevicePanel + + + Dongle ID + Dongle ID + + + + N/A + ไม่มี + + + + Serial + ซีเรียล + + + + Driver Camera + กล้องฝั่งคนขับ + + + + PREVIEW + แสดงภาพ + + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + ดูภาพตัวอย่างกล้องที่หันเข้าหาคนขับเพื่อให้แน่ใจว่าการตรวจสอบคนขับมีทัศนวิสัยที่ดี (รถต้องดับเครื่องยนต์) + + + + Reset Calibration + รีเซ็ตการคาลิเบรท + + + + RESET + รีเซ็ต + + + + Are you sure you want to reset calibration? + คุณแน่ใจหรือไม่ว่าต้องการรีเซ็ตการคาลิเบรท? + + + + Review Training Guide + ทบทวนคู่มือการใช้งาน + + + + REVIEW + ทบทวน + + + + Review the rules, features, and limitations of openpilot + ตรวจสอบกฎ คุณสมบัติ และข้อจำกัดของ openpilot + + + + Are you sure you want to review the training guide? + คุณแน่ใจหรือไม่ว่าต้องการทบทวนคู่มือการใช้งาน? + + + + Regulatory + ระเบียบข้อบังคับ + + + + VIEW + ดู + + + + Change Language + เปลี่ยนภาษา + + + + CHANGE + เปลี่ยน + + + + Select a language + เลือกภาษา + + + + Reboot + รีบูต + + + + Power Off + ปิดเครื่อง + + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot กำหนดให้ติดตั้งอุปกรณ์ โดยสามารถเอียงด้านซ้ายหรือขวาไม่เกิน 4° และเอียงขึ้นด้านบนไม่เกิน 5° หรือเอียงลงด้านล่างไม่เกิน 8° openpilot ทำการคาลิเบรทอย่างต่อเนื่อง แทบจะไม่จำเป็นต้องทำการรีเซ็ตการคาลิเบรท + + + + Your device is pointed %1° %2 and %3° %4. + อุปกรณ์ของคุณเอียงไปทาง %2 %1° และ %4 %3° + + + + down + ด้านล่าง + + + + up + ด้านบน + + + + left + ด้านซ้าย + + + + right + ด้านขวา + + + + Are you sure you want to reboot? + คุณแน่ใจหรือไม่ว่าต้องการรีบูต? + + + + Disengage to Reboot + ยกเลิกระบบช่วยขับเพื่อรีบูต + + + + Are you sure you want to power off? + คุณแน่ใจหรือไม่ว่าต้องการปิดเครื่อง? + + + + Disengage to Power Off + ยกเลิกระบบช่วยขับเพื่อปิดเครื่อง + + + + DriveStats + + + Drives + การขับขี่ + + + + Hours + ชั่วโมง + + + + ALL TIME + ทั้งหมด + + + + PAST WEEK + สัปดาห์ที่ผ่านมา + + + + KM + กิโลเมตร + + + + Miles + ไมล์ + + + + DriverViewScene + + + camera starting + กำลังเปิดกล้อง + + + + InputDialog + + + Cancel + ยกเลิก + + + + Need at least %n character(s)! + + ต้องการอย่างน้อย %n ตัวอักษร! + + + + + Installer + + + Installing... + กำลังติดตั้ง... + + + + Receiving objects: + กำลังรับข้อมูล: + + + + Resolving deltas: + การแก้ไขเดลต้า: + + + + Updating files: + กำลังอัปเดตไฟล์: + + + + MapETA + + + eta + eta + + + + min + นาที + + + + hr + ชม. + + + + km + กม. + + + + mi + ไมล์ + + + + MapInstructions + + + km + กม. + + + + m + ม. + + + + mi + ไมล์ + + + + ft + ฟุต + + + + MapPanel + + + Current Destination + ปลายทางปัจจุบัน + + + + CLEAR + ล้างข้อมูล + + + + Recent Destinations + ปลายทางล่าสุด + + + + Try the Navigation Beta + ลองใช้ระบบนำทาง (เบต้า) + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + รับการแสดงเส้นทางแบบเลี้ยวต่อเลี้ยว และอื่นๆ ด้วยการสมัครบริการ +comma prime สมัครเลย: https://connect.comma.ai + + + + No home +location set + ยังไม่ได้กำหนด +ตำแหน่งของบ้าน + + + + No work +location set + ยังไม่ได้กำหนด +ตำแหน่งของที่ทำงาน + + + + no recent destinations + ไม่พบปลายทางล่าสุด + + + + MapWindow + + + Map Loading + กำลังโหลดแผนที่ + + + + Waiting for GPS + กำลังรอสัญญาณ GPS + + + + MultiOptionDialog + + + Select + เลือก + + + + Cancel + ยกเลิก + + + + Networking + + + Advanced + ขั้นสูง + + + + Enter password + ใส่รหัสผ่าน + + + + + for "%1" + สำหรับ "%1" + + + + Wrong password + รหัสผ่านผิด + + + + NvgWindow + + + km/h + กม./ชม. + + + + mph + ไมล์/ชม. + + + + + MAX + สูงสุด + + + + + SPEED + ความเร็ว + + + + + LIMIT + จำกัด + + + + OffroadHome + + + UPDATE + อัปเดต + + + + ALERTS + การแจ้งเตือน + + + + ALERT + การแจ้งเตือน + + + + PairingPopup + + + Pair your device to your comma account + จับคู่อุปกรณ์ของคุณกับบัญชี comma ของคุณ + + + + Go to https://connect.comma.ai on your phone + ไปที่ https://connect.comma.ai ด้วยโทรศัพท์ของคุณ + + + + Click "add new device" and scan the QR code on the right + กดที่ "add new device" และสแกนคิวอาร์โค้ดทางด้านขวา + + + + Bookmark connect.comma.ai to your home screen to use it like an app + จดจำ connect.comma.ai โดยการเพิ่มไปยังหน้าจอโฮม เพื่อใช้งานเหมือนเป็นแอปพลิเคชัน + + + + PrimeAdWidget + + + Upgrade Now + อัพเกรดเดี๋ยวนี้ + + + + Become a comma prime member at connect.comma.ai + สมัครสมาชิก comma prime ได้ที่ connect.comma.ai + + + + PRIME FEATURES: + คุณสมบัติของ PRIME: + + + + Remote access + การเข้าถึงระยะไกล + + + + 1 year of storage + จัดเก็บข้อมูลนาน 1 ปี + + + + Developer perks + สิทธิพิเศษสำหรับนักพัฒนา + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ สมัครสำเร็จ + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + คะแนน COMMA + + + + QObject + + + Reboot + รีบูต + + + + Exit + ปิด + + + + dashcam + กล้องติดรถยนต์ + + + + openpilot + openpilot + + + + %n minute(s) ago + + %n นาทีที่แล้ว + + + + + %n hour(s) ago + + %n ชั่วโมงที่แล้ว + + + + + %n day(s) ago + + %n วันที่แล้ว + + + + + Reset + + + Reset failed. Reboot to try again. + การรีเซ็ตล้มเหลว รีบูตเพื่อลองอีกครั้ง + + + + Are you sure you want to reset your device? + คุณแน่ใจหรือไม่ว่าต้องการรีเซ็ตอุปกรณ์? + + + + Resetting device... + กำลังรีเซ็ตอุปกรณ์... + + + + System Reset + รีเซ็ตระบบ + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + มีการสั่งรีเซ็ตระบบ กดยืนยันเพื่อลบข้อมูลและการตั้งค่าทั้งหมด กดยกเลิกเพื่อบูตเข้าระบบตามปกติ + + + + Cancel + ยกเลิก + + + + Reboot + รีบูต + + + + Confirm + ยืนยัน + + + + Unable to mount data partition. Press confirm to reset your device. + ไม่สามารถเมานต์พาร์ติชั่นข้อมูล กดยืนยันเพื่อรีเซ็ตอุปกรณ์ของคุณ + + + + RichTextDialog + + + Ok + ตกลง + + + + SettingsWindow + + + × + × + + + + Device + อุปกรณ์ + + + + + Network + เครือข่าย + + + + Toggles + ตัวเลือก + + + + Software + ซอฟต์แวร์ + + + + Navigation + การนำทาง + + + + Setup + + + WARNING: Low Voltage + คำเตือน: แรงดันไฟฟ้าต่ำ + + + + Power your device in a car with a harness or proceed at your own risk. + โปรดต่ออุปกรณ์ของคุณเข้ากับสายควบคุมในรถยนต์ หรือดำเนินการด้วยความเสี่ยงของคุณเอง + + + + Power off + ปิดเครื่อง + + + + + + Continue + ดำเนินการต่อ + + + + Getting Started + เริ่มกันเลย + + + + Before we get on the road, let’s finish installation and cover some details. + ก่อนออกเดินทาง เรามาทำการติดตั้งซอฟต์แวร์ และตรวจสอบการตั้งค่า + + + + Connect to Wi-Fi + เชื่อมต่อ Wi-Fi + + + + + Back + ย้อนกลับ + + + + Continue without Wi-Fi + ดำเนินการต่อโดยไม่ใช้ Wi-Fi + + + + Waiting for internet + กำลังรอสัญญาณอินเตอร์เน็ต + + + + Choose Software to Install + เลือกซอฟต์แวร์ที่จะติดตั้ง + + + + Dashcam + กล้องติดรถยนต์ + + + + Custom Software + ซอฟต์แวร์ที่กำหนดเอง + + + + Enter URL + ป้อน URL + + + + for Custom Software + สำหรับซอฟต์แวร์ที่กำหนดเอง + + + + Downloading... + กำลังดาวน์โหลด... + + + + Download Failed + ดาวน์โหลดล้มเหลว + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + ตรวจสอบให้แน่ใจว่า URL ที่ป้อนนั้นถูกต้อง และอุปกรณ์เชื่อมต่ออินเทอร์เน็ตอยู่ + + + + Reboot device + รีบูตอุปกรณ์ + + + + Start over + เริ่มต้นใหม่ + + + + SetupWidget + + + Finish Setup + ตั้งค่าเสร็จสิ้น + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + จับคู่อุปกรณ์ของคุณกับ comma connect (connect.comma.ai) และรับข้อเสนอ comma prime ของคุณ + + + + Pair device + จับคู่อุปกรณ์ + + + + Sidebar + + + + CONNECT + เชื่อมต่อ + + + + OFFLINE + ออฟไลน์ + + + + + ONLINE + ออนไลน์ + + + + ERROR + เกิดข้อผิดพลาด + + + + + + TEMP + อุณหภูมิ + + + + HIGH + สูง + + + + GOOD + ดี + + + + OK + พอใช้ + + + + VEHICLE + รถยนต์ + + + + NO + ไม่พบ + + + + PANDA + PANDA + + + + GPS + จีพีเอส + + + + SEARCH + ค้นหา + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Git Branch + + + + Git Commit + Git Commit + + + + OS Version + เวอร์ชันระบบปฏิบัติการ + + + + Version + เวอร์ชั่น + + + + Last Update Check + ตรวจสอบการอัปเดตล่าสุด + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + ครั้งสุดท้ายที่ openpilot ตรวจสอบการอัปเดตสำเร็จ ตัวอัปเดตจะทำงานในขณะที่รถดับเครื่องอยู่เท่านั้น + + + + Check for Update + ตรวจสอบการอัปเดต + + + + CHECKING + กำลังตรวจสอบ + + + + Switch Branch + เปลี่ยน Branch + + + + ENTER + เปลี่ยน + + + + + The new branch will be pulled the next time the updater runs. + Branch ใหม่จะถูกติดตั้งในครั้งต่อไปที่ตัวอัปเดตทำงาน + + + + Enter branch name + ใส่ชื่อ Branch + + + + Uninstall %1 + ถอนการติดตั้ง %1 + + + + UNINSTALL + ถอนการติดตั้ง + + + + Are you sure you want to uninstall? + คุณแน่ใจหรือไม่ว่าต้องการถอนการติดตั้ง? + + + + failed to fetch update + โหลดข้อมูลอัปเดตไม่สำเร็จ + + + + + CHECK + ตรวจสอบ + + + + SshControl + + + SSH Keys + คีย์ SSH + + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + คำเตือน: สิ่งนี้ให้สิทธิ์ SSH เข้าถึงคีย์สาธารณะทั้งหมดใน GitHub ของคุณ อย่าป้อนชื่อผู้ใช้ GitHub อื่นนอกเหนือจากของคุณเอง พนักงาน comma จะไม่ขอให้คุณเพิ่มชื่อผู้ใช้ GitHub ของพวกเขา + + + + + ADD + เพิ่ม + + + + Enter your GitHub username + ป้อนชื่อผู้ใช้ GitHub ของคุณ + + + + LOADING + กำลังโหลด + + + + REMOVE + ลบ + + + + Username '%1' has no keys on GitHub + ชื่อผู้ใช้ '%1' ไม่มีคีย์บน GitHub + + + + Request timed out + ตรวจสอบไม่สำเร็จ เนื่องจากใช้เวลามากเกินไป + + + + Username '%1' doesn't exist on GitHub + ไม่พบชื่อผู้ใช้ '%1' บน GitHub + + + + SshToggle + + + Enable SSH + เปิดใช้งาน SSH + + + + TermsPage + + + Terms & Conditions + ข้อตกลงและเงื่อนไข + + + + Decline + ปฏิเสธ + + + + Scroll to accept + เลื่อนเพื่อตอบรับข้อตกลง + + + + Agree + ยอมรับ + + + + TogglesPanel + + + Enable openpilot + เปิดใช้งาน openpilot + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + ใช้ระบบ openpilot สำหรับระบบควบคุมความเร็วอัตโนมัติ และระบบช่วยควบคุมรถให้อยู่ในเลน คุณจำเป็นต้องให้ความสนใจตลอดเวลาที่ใช้คุณสมบัตินี้ การเปลี่ยนการตั้งค่านี้จะมีผลเมื่อคุณดับเครื่องยนต์ + + + + Enable Lane Departure Warnings + เปิดใช้งานการเตือนการออกนอกเลน + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + รับการแจ้งเตือนให้เลี้ยวกลับเข้าเลนเมื่อรถของคุณตรวจพบการข้ามช่องจราจรโดยไม่เปิดสัญญาณไฟเลี้ยวในขณะขับขี่ที่ความเร็วเกิน 31 ไมล์ต่อชั่วโมง (50 กม./ชม) + + + + Use Metric System + ใช้ระบบเมตริก + + + + Display speed in km/h instead of mph. + แสดงความเร็วเป็น กม./ชม. แทน ไมล์/ชั่วโมง + + + + Record and Upload Driver Camera + บันทึกและอัปโหลดภาพจากกล้องคนขับ + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + อัปโหลดข้อมูลจากกล้องที่หันหน้าไปทางคนขับ และช่วยปรับปรุงอัลกอริธึมการตรวจสอบผู้ขับขี่ + + + + Disengage On Accelerator Pedal + ยกเลิกระบบช่วยขับเมื่อเหยียบคันเร่ง + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + เมื่อเปิดใช้งาน การกดแป้นคันเร่งจะเป็นการยกเลิกระบบช่วยขับโดย openpilot + + + + Show ETA in 24h Format + แสดงเวลา ETA ในรูปแบบ 24 ชั่วโมง + + + + Use 24h format instead of am/pm + ใช้รูปแบบเวลา 24 ชั่วโมง แทน am/pm + + + + Show Map on Left Side of UI + แสดงแผนที่ที่ด้านซ้ายของหน้าจอ + + + + Show map on left side when in split screen view. + แสดงแผนที่ด้านซ้ายของหน้าจอเมื่ออยู่ในโหมดแบ่งหน้าจอ + + + + openpilot Longitudinal Control + openpilot การควบคุมการเร่งและลดความเร็ว + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilot จะปิดการใช้งานเรดาร์ของรถ และจะเข้าควบคุมการเร่งและเบรก คำเตือน: สิ่งนี้จะปิดระบบ AEB! + + + + Updater + + + Update Required + จำเป็นต้องอัปเดต + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + จำเป็นต้องมีการอัปเดตระบบปฏิบัติการ เชื่อมต่ออุปกรณ์ของคุณกับ Wi-Fi เพื่อประสบการณ์การอัปเดตที่เร็วที่สุด ขนาดดาวน์โหลดประมาณ 1GB + + + + Connect to Wi-Fi + เชื่อมต่อกับ Wi-Fi + + + + Install + ติดตั้ง + + + + Back + ย้อนกลับ + + + + Loading... + กำลังโหลด... + + + + Reboot + รีบูต + + + + Update failed + การอัปเดตล้มเหลว + + + + WifiUI + + + + Scanning for networks... + กำลังสแกนหาเครือข่าย... + + + + CONNECTING... + กำลังเชื่อมต่อ... + + + + FORGET + เลิกใช้ + + + + Forget Wi-Fi Network "%1"? + เลิกใช้เครือข่าย Wi-Fi "%1"? + + + diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1ed96422b060f7..a26cddc0c34859 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -874,71 +874,71 @@ location set Sidebar - - + + CONNECT CONNECT - + OFFLINE 离线 - - + + ONLINE 在线 - + ERROR 连接出错 - - - + + + TEMP 设备温度 - + HIGH 过热 - + GOOD 良好 - + OK 一般 - + VEHICLE 车辆连接 - + NO - + PANDA PANDA - + GPS GPS - + SEARCH 搜索中 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 4f5c37764f87e0..f4681f85d940c2 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 雲端服務 - + OFFLINE 已離線 - - + + ONLINE 已連線 - + ERROR 錯誤 - - - + + + TEMP 溫度 - + HIGH 偏高 - + GOOD 正常 - + OK 一般 - + VEHICLE 車輛通訊 - + NO 未連線 - + PANDA 車輛通訊 - + GPS GPS - + SEARCH 車輛通訊 diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index e4a3146a69c02c..6b419ca9d80908 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -18,6 +18,7 @@ const std::initializer_list> keyboard_shortc {"space", "Pause/Resume"}, {"e", "Next Engagement"}, {"d", "Next Disengagement"}, + {"t", "Next User Tag"} }, { {"enter", "Enter seek request"}, @@ -32,6 +33,7 @@ enum Color { Yellow, Green, Red, + Cyan, BrightWhite, Engaged, Disengaged, @@ -70,6 +72,7 @@ ConsoleUI::ConsoleUI(Replay *replay, QObject *parent) : replay(replay), sm({"car init_pair(Color::Debug, 246, COLOR_BLACK); // #949494 init_pair(Color::Yellow, 184, COLOR_BLACK); init_pair(Color::Red, COLOR_RED, COLOR_BLACK); + init_pair(Color::Cyan, COLOR_CYAN, COLOR_BLACK); init_pair(Color::BrightWhite, 15, COLOR_BLACK); init_pair(Color::Disengaged, COLOR_BLUE, COLOR_BLUE); init_pair(Color::Engaged, 28, 28); @@ -205,6 +208,7 @@ void ConsoleUI::displayTimelineDesc() { {Color::Green, " Info ", true}, {Color::Yellow, " Warning ", true}, {Color::Red, " Critical ", true}, + {Color::Cyan, " User Tag ", true}, }; for (auto [color, name, bold] : indicators) { add_str(w[Win::TimelineDesc], "__", color, bold); @@ -263,6 +267,8 @@ void ConsoleUI::updateTimeline() { if (type == TimelineType::Engaged) { mvwchgat(win, 1, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); mvwchgat(win, 2, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); + } else if (type == TimelineType::UserFlag) { + mvwchgat(win, 3, start_pos, end_pos - start_pos + 1, ACS_S3, Color::Cyan, NULL); } else { auto color_id = Color::Green; if (type != TimelineType::AlertInfo) { @@ -336,6 +342,8 @@ void ConsoleUI::handleKey(char c) { replay->seekToFlag(FindFlag::nextEngagement); } else if (c == 'd') { replay->seekToFlag(FindFlag::nextDisEngagement); + } else if (c == 't') { + replay->seekToFlag(FindFlag::nextUserFlag); } else if (c == 'm') { replay->seekTo(+60, true); } else if (c == 'M') { diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index c886a7e1862ae3..4b983fff85969d 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -149,6 +149,9 @@ void Replay::buildTimeline() { timeline.push_back({toSeconds(alert_begin), toSeconds(e->mono_time), alert_type}); alert_begin = 0; } + } else if (e->which == cereal::Event::Which::USER_FLAG) { + std::lock_guard lk(timeline_lock); + timeline.push_back({toSeconds(e->mono_time), toSeconds(e->mono_time), TimelineType::UserFlag}); } } } @@ -163,6 +166,10 @@ std::optional Replay::find(FindFlag flag) { } else if (flag == FindFlag::nextDisEngagement && end_ts > cur_ts) { return end_ts; } + } else if (type == TimelineType::UserFlag) { + if (flag == FindFlag::nextUserFlag && start_ts > cur_ts) { + return start_ts; + } } } return std::nullopt; @@ -360,7 +367,7 @@ void Replay::stream() { setCurrentSegment(toSeconds(cur_mono_time_) / 60); // migration for pandaState -> pandaStates to keep UI working for old segments - if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D && + if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D && sockets_[cereal::Event::Which::PANDA_STATES] != nullptr) { MessageBuilder msg; auto ps = msg.initEvent().initPandaStates(1); diff --git a/tools/replay/replay.h b/tools/replay/replay.h index 13269d3ec9a269..86d609683a5034 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -24,10 +24,11 @@ enum REPLAY_FLAGS { enum class FindFlag { nextEngagement, - nextDisEngagement + nextDisEngagement, + nextUserFlag, }; -enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical }; +enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserFlag }; class Replay : public QObject { Q_OBJECT diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index fa4ce2b41d9742..f008b9e716cde9 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -179,7 +179,7 @@ def gps_callback(gps, vehicle_state): ] dat.gpsLocationExternal = { - "timestamp": int(time.time() * 1000), + "unixTimestampMillis": int(time.time() * 1000), "flags": 1, # valid fix "accuracy": 1.0, "verticalAccuracy": 1.0, diff --git a/update_requirements.sh b/update_requirements.sh index 94b14496f151a9..719a28c3599ead 100755 --- a/update_requirements.sh +++ b/update_requirements.sh @@ -4,11 +4,26 @@ set -e DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" cd $DIR +RC_FILE="${HOME}/.$(basename ${SHELL})rc" +if [ "$(uname)" == "Darwin" ] && [ $SHELL == "/bin/bash" ]; then + RC_FILE="$HOME/.bash_profile" +fi + if ! command -v "pyenv" > /dev/null 2>&1; then echo "pyenv install ..." curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash - export PATH=$HOME/.pyenv/bin:$HOME/.pyenv/shims:$PATH + + echo -e "\n. ~/.pyenvrc" >> $RC_FILE + cat < "${HOME}/.pyenvrc" +if [ -z "\$PYENV_ROOT" ]; then + export PATH=\$HOME/.pyenv/bin:\$HOME/.pyenv/shims:\$PATH + export PYENV_ROOT="\$HOME/.pyenv" + eval "\$(pyenv init -)" + eval "\$(pyenv virtualenv-init -)" +fi +EOF fi +source $RC_FILE export MAKEFLAGS="-j$(nproc)"