diff --git a/.github/workflows/prebuilt.yaml b/.github/workflows/prebuilt.yaml
index 7acc8a2254..99d9694f24 100644
--- a/.github/workflows/prebuilt.yaml
+++ b/.github/workflows/prebuilt.yaml
@@ -25,7 +25,7 @@ jobs:
IMAGE_NAME: openpilot-prebuilt
steps:
- name: Wait for green check mark
- uses: commaai/wait-on-check-action@f16fc3bb6cd4886520b4e9328db1d42104d5cadc
+ uses: lewagon/wait-on-check-action@e2558238c09778af25867eb5de5a3ce4bbae3dcd
with:
ref: master
wait-interval: 30
diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml
index fb5a37eeef..8df89dcc38 100644
--- a/.github/workflows/release.yaml
+++ b/.github/workflows/release.yaml
@@ -12,7 +12,7 @@ jobs:
if: github.repository == 'commaai/openpilot'
steps:
- name: Wait for green check mark
- uses: commaai/wait-on-check-action@f16fc3bb6cd4886520b4e9328db1d42104d5cadc
+ uses: lewagon/wait-on-check-action@e2558238c09778af25867eb5de5a3ce4bbae3dcd
with:
ref: master
wait-interval: 30
diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml
index 99a21b58f3..fbc0d94194 100644
--- a/.github/workflows/selfdrive_tests.yaml
+++ b/.github/workflows/selfdrive_tests.yaml
@@ -17,12 +17,12 @@ 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 $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 $BASE_IMAGE /bin/sh -c
BUILD_CL: |
docker pull $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest || true
docker build --cache-from $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest -t $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest -t $CL_BASE_IMAGE:latest -f Dockerfile.openpilot_base_cl .
- RUN_CL: 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 $CL_BASE_IMAGE /bin/sh -c
+ RUN_CL: 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 $CL_BASE_IMAGE /bin/sh -c
UNIT_TEST: coverage run --append -m unittest discover
@@ -58,6 +58,9 @@ jobs:
run: |
TARGET_DIR=$STRIPPED_DIR release/build_devel.sh
cp Dockerfile.openpilot_base $STRIPPED_DIR
+ cp .pre-commit-config.yaml $STRIPPED_DIR
+ cp .pylintrc $STRIPPED_DIR
+ cp mypy.ini $STRIPPED_DIR
- name: Build Docker image
run: |
eval "$BUILD"
@@ -66,6 +69,10 @@ jobs:
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"
@@ -510,3 +517,67 @@ jobs:
run: |
$DOCKER_LOGIN
docker push $DOCKER_REGISTRY/openpilot-docs:latest
+
+ car_docs_diff:
+ name: comment on PR with car docs diff
+ runs-on: ubuntu-20.04
+ timeout-minutes: 50
+ if: github.event_name == 'pull_request'
+ steps:
+ - uses: actions/checkout@v3
+ 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"
+ - 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"
+ sudo chown -R $USER:$USER ${{ github.workspace }}
+ - uses: actions/checkout@v3
+ with:
+ submodules: true
+ - name: Save car docs diff
+ id: save_diff
+ run: |
+ ${{ env.RUN }} "scons -j$(nproc)"
+ output=$(${{ env.RUN }} "python selfdrive/debug/print_docs_diff.py --path /tmp/openpilot_cache/base_car_info")
+ output="${output//$'\n'/'%0A'}"
+ echo "::set-output name=diff::$output"
+ - name: Find comment
+ if: ${{ env.AZURE_TOKEN != '' }}
+ uses: peter-evans/find-comment@1769778a0c5bd330272d749d12c036d65e70d39d
+ id: fc
+ with:
+ issue-number: ${{ github.event.pull_request.number }}
+ body-includes: This PR makes changes to
+ - name: Update comment
+ if: ${{ steps.save_diff.outputs.diff != '' && env.AZURE_TOKEN != '' }}
+ uses: peter-evans/create-or-update-comment@b95e16d2859ad843a14218d1028da5b2c4cbc4b4
+ with:
+ comment-id: ${{ steps.fc.outputs.comment-id }}
+ issue-number: ${{ github.event.pull_request.number }}
+ body: "${{ steps.save_diff.outputs.diff }}"
+ edit-mode: replace
+ - name: Delete comment
+ if: ${{ steps.fc.outputs.comment-id != '' && steps.save_diff.outputs.diff == '' && env.AZURE_TOKEN != '' }}
+ uses: actions/github-script@v6
+ with:
+ script: |
+ github.rest.issues.deleteComment({
+ owner: context.repo.owner,
+ repo: context.repo.repo,
+ comment_id: ${{ steps.fc.outputs.comment-id }}
+ })
diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml
index b901e07721..8b8bc1f1b9 100644
--- a/.pre-commit-config.yaml
+++ b/.pre-commit-config.yaml
@@ -54,7 +54,7 @@ repos:
entry: cppcheck
language: system
types: [c++]
- exclude: '^(third_party/)|(pyextra/)|(cereal/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)/|(installer/)'
+ exclude: '^(third_party/)|(pyextra/)|(cereal/)|(rednose/)|(rednose_repo/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)/|(installer/)'
args:
- --error-exitcode=1
- --language=c++
diff --git a/README.md b/README.md
index 34b17625f9..3dce9d4475 100755
--- a/README.md
+++ b/README.md
@@ -105,23 +105,25 @@ Directory Structure
├── third_party # External libraries
├── pyextra # Extra python packages
└── system # Generic services
+ ├── camerad # Driver to capture images from the camera sensors
+ ├── clocksd # Broadcasts current time
+ ├── hardware # Hardware abstraction classes
├── logcatd # systemd journal as a service
└── proclogd # Logs information from /proc
└── selfdrive # Code needed to drive the car
├── assets # Fonts, images, and sounds for UI
├── athena # Allows communication with the app
├── boardd # Daemon to talk to the board
- ├── camerad # Driver to capture images from the camera sensors
├── car # Car specific code to read states and control actuators
- ├── common # Shared C/C++ code for the daemons
├── controls # Planning and controls
├── debug # Tools to help you debug and do car ports
├── locationd # Precise localization and vehicle parameter estimation
├── loggerd # Logger and uploader of car data
+ ├── manager # Deamon that starts/stops all other daemons as needed
├── modeld # Driving and monitoring model runners
- ├── proclogd # Logs information from proc
- ├── sensord # IMU interface code
+ ├── monitoring # Daemon to determine driver attention
├── navd # Turn-by-turn navigation
+ ├── sensord # IMU interface code
├── test # Unit tests, system tests, and a car simulator
└── ui # The UI
diff --git a/RELEASES.md b/RELEASES.md
index b87bd2ee7d..b47a18a3de 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,3 +1,6 @@
+Version 0.8.16 (2022-XX-XX)
+========================
+
Version 0.8.15 (2022-07-20)
========================
* New driving model
diff --git a/cereal b/cereal
index cda60ec965..a4c1afa3bf 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit cda60ec9652c05de4ccfcad1fae7936e708434a3
+Subproject commit a4c1afa3bfcbba989c128ec9b5092f6c91f4da22
diff --git a/common/modeldata.h b/common/modeldata.h
index b193841416..e13840d53e 100644
--- a/common/modeldata.h
+++ b/common/modeldata.h
@@ -34,12 +34,13 @@ const mat3 ecam_intrinsic_matrix = (mat3){{567.0, 0.0, 1928.0 / 2,
0.0, 567.0, 1208.0 / 2,
0.0, 0.0, 1.0}};
-static inline mat3 get_model_yuv_transform(bool bayer = true) {
+static inline mat3 get_model_yuv_transform() {
float db_s = 1.0;
const mat3 transform = (mat3){{
1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0
}};
- return bayer ? transform_scale_buffer(transform, db_s) : transform;
+ // Can this be removed since scale is 1?
+ return transform_scale_buffer(transform, db_s);
}
diff --git a/common/version.h b/common/version.h
index de550d6be5..bf1c58df1e 100644
--- a/common/version.h
+++ b/common/version.h
@@ -1 +1 @@
-#define COMMA_VERSION "0.8.15"
+#define COMMA_VERSION "0.8.16"
diff --git a/docs/CARS.md b/docs/CARS.md
index 8e398e1fc1..e4abe3004c 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -35,7 +35,7 @@ How We Rate The Cars
**All supported cars can move between the tiers as support changes.**
-# Gold - 31 cars
+# Gold - 30 cars
|Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained|
|---|---|---|:---:|:---:|:---:|:---:|:---:|
@@ -49,18 +49,17 @@ How We Rate The Cars
|Kia|Niro Electric 2021|All||
|
|
|
|
|Kia|Niro Electric 2022|All|
|
|
|
|
|
|Kia|Telluride 2020|SCC + LKAS|
|
|
|
|
|
-|Lexus|ES 2019-21|All|
|
|
|
|
|
+|Lexus|ES 2019-22|All|
|
|
|
|
|
|Lexus|ES Hybrid 2019-22|All|
|
|
|
|
|
-|Lexus|NX 2020|All|
|
|
|
|
|
-|Lexus|NX Hybrid 2020|All|
|
|
|
|
|
+|Lexus|NX 2020-21|All|
|
|
|
|
|
+|Lexus|NX Hybrid 2020-21|All|
|
|
|
|
|
|Lexus|RX 2020-22|All|
|
|
|
|
|
-|Lexus|UX Hybrid 2019-21|All|
|
|
|
|
|
+|Lexus|UX Hybrid 2019-22|All|
|
|
|
|
|
|Toyota|Avalon 2022|All|
|
|
|
|
|
|Toyota|Avalon Hybrid 2022|All|
|
|
|
|
|
|Toyota|Camry 2021-22|All|
|
[4](#footnotes)|
|
|
|
|Toyota|Camry Hybrid 2021-22|All|
|
|
|
|
|
|Toyota|Corolla 2020-22|All|
|
|
|
|
|
-|Toyota|Corolla Cross 2020-21 (Non-US only)|All|
|
|
|
|
|
|Toyota|Corolla Hatchback 2019-22|All|
|
|
|
|
|
|Toyota|Corolla Hybrid 2020-22|All|
|
|
|
|
|
|Toyota|Highlander 2020-22|All|
|
|
|
|
|
@@ -71,7 +70,7 @@ How We Rate The Cars
|Toyota|RAV4 2019-21|All|
|
|
|
|
|
|Toyota|RAV4 Hybrid 2019-21|All|
|
|
|
|
|
-# Silver - 69 cars
+# Silver - 78 cars
|Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained|
|---|---|---|:---:|:---:|:---:|:---:|:---:|
@@ -80,8 +79,8 @@ How We Rate The Cars
|Audi|RS3 2018|ACC + Lane Assist|
|
|
|
|
|
|Audi|S3 2015-17|ACC + Lane Assist|
|
|
|
|
|
|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|
|
|
|
|
|
-|Genesis|G70 2018|All|
|
|
|
|
|
-|Genesis|G80 2018|All|
|
|
|
|
|
+|Genesis|G70 2018-19|All|
|
|
|
|
|
+|Genesis|G80 2017-19|All|
|
|
|
|
|
|Hyundai|Elantra 2021-22|SCC + LKAS|
|
|
|
|
|
|Hyundai|Elantra Hybrid 2021-22|SCC + LKAS|
|
|
|
|
|
|Hyundai|Ioniq Electric 2020|SCC + LKAS|
|
|
|
|
|
@@ -105,7 +104,7 @@ How We Rate The Cars
|Kia|Seltos 2021|SCC + LKAS|
|
|
|
|
|
|Kia|Sorento 2018|SCC + LKAS|
|
|
|
|
|
|Kia|Sorento 2019|SCC + LKAS|
|
|
|
|
|
-|Kia|Stinger 2018|SCC + LKAS|
|
|
|
|
|
+|Kia|Stinger 2018-20|SCC + LKAS|
|
|
|
|
|
|Lexus|CT Hybrid 2017-18|LSS|
[3](#footnotes)|
|
|
|
|
|Lexus|ES Hybrid 2017-18|LSS|
[3](#footnotes)|
|
|
|
|
|Lexus|NX 2018-19|All|
[3](#footnotes)|
|
|
|
|
@@ -117,15 +116,17 @@ How We Rate The Cars
|Nissan|X-Trail 2017|ProPILOT|
|
|
|
|
|
|SEAT|Ateca 2018|Driver Assistance|
|
|
|
|
|
|SEAT|Leon 2014-20|Driver Assistance|
|
|
|
|
|
-|Subaru|Ascent 2019-20|All|
|
|
|
|
|
+|Subaru|Ascent 2019-21|All|
|
|
|
|
|
|Subaru|Crosstrek 2020-21|EyeSight|
|
|
|
|
|
-|Subaru|Forester 2019-21|All|
|
|
|
|
|
-|Subaru|Impreza 2020-21|EyeSight|
|
|
|
|
|
+|Subaru|Forester 2019-22|All|
|
|
|
|
|
+|Subaru|Impreza 2020-22|EyeSight|
|
|
|
|
|
|Subaru|XV 2020-21|EyeSight|
|
|
|
|
|
|Toyota|Alphard 2019-20|All|
|
|
|
|
|
|Toyota|Alphard Hybrid 2021|All|
|
|
|
|
|
|Toyota|Camry 2018-20|All|
|
[4](#footnotes)|
|
|
|
|Toyota|Camry Hybrid 2018-20|All|
|
[4](#footnotes)|
|
|
|
+|Toyota|Corolla Cross 2020-21 (Non-US only)|All|
|
|
|
|
|
+|Toyota|Corolla Cross Hybrid 2020-22 (Non-US only)|All|
|
|
|
|
|
|Toyota|Highlander 2017-19|All|
[3](#footnotes)|
|
|
|
|
|Toyota|Highlander Hybrid 2017-19|All|
[3](#footnotes)|
|
|
|
|
|Toyota|Prius 2016-20|TSS-P|
[3](#footnotes)|
|
|
|
|
@@ -133,25 +134,32 @@ How We Rate The Cars
|Toyota|RAV4 2022|All|
|
|
|
|
|
|Toyota|RAV4 Hybrid 2016-18|TSS-P|
[3](#footnotes)|
|
|
|
|
|Toyota|RAV4 Hybrid 2022|All|
|
|
|
|
|
-|Volkswagen|Atlas 2018-19, 2022[7](#footnotes)|Driver Assistance|
|
|
|
|
|
-|Volkswagen|e-Golf 2014, 2018-20|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf 2015-20|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf Alltrack 2017-18|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf GTE 2016|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf GTI 2018-21|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf R 2016-19|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf SportsVan 2016|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Golf SportWagen 2015|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Passat 2015-19[6](#footnotes)|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Polo 2020|Driver Assistance|
|
|
|
|
|
-
-# Bronze - 80 cars
+|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|e-Golf 2014-20|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf 2015-20[8](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf Alltrack 2015-19|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf GTD 2015-20|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf GTE 2015-20|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf GTI 2015-21|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf R 2015-19[8](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Golf SportsVan 2015-20|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Passat 2015-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Passat GTE 2015-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Polo 2020-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Teramont 2018-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Teramont X 2021-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+
+# Bronze - 83 cars
|Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained|
|---|---|---|:---:|:---:|:---:|:---:|:---:|
|Acura|ILX 2016-19|AcuraWatch Plus|
|
|
|
|
|
|Acura|RDX 2016-18|AcuraWatch Plus|
|
|
|
|
|
-|Acura|RDX 2019-21|All|
|
|
|
|
|
+|Acura|RDX 2019-22|All|
|
|
|
|
|
|Audi|Q2 2018|ACC + Lane Assist|
|
|
|
|
|
|Audi|Q3 2020-21|ACC + Lane Assist|
|
|
|
|
|
|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|
|
|
|
|
|
@@ -159,27 +167,27 @@ How We Rate The Cars
|Chrysler|Pacifica 2019-20|Adaptive Cruise|
|
|
|
|
|
|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|
|
|
|
|
|
|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise|
|
|
|
|
|
-|Genesis|G90 2018|All|
|
|
|
|
|
+|Genesis|G90 2017-18|All|
|
|
|
|
|
|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|
|
|
|
|
|
-|Honda|Accord 2018-21|All|
|
|
|
|
|
-|Honda|Accord Hybrid 2018-21|All|
|
|
|
|
|
+|Honda|Accord 2018-22|All|
|
|
|
|
|
+|Honda|Accord Hybrid 2018-22|All|
|
|
|
|
|
|Honda|Civic 2016-18|Honda Sensing|
|
|
|
|
|
-|Honda|Civic 2019-20|All|
|
|
[2](#footnotes)|
|
|
+|Honda|Civic 2019-21|All|
|
|
[2](#footnotes)|
|
|
|Honda|Civic 2022|All|
|
|
|
|
|
|Honda|Civic Hatchback 2017-21|Honda Sensing|
|
|
|
|
|
|Honda|Civic Hatchback 2022|All|
|
|
|
|
|
|Honda|CR-V 2015-16|Touring|
|
|
|
|
|
-|Honda|CR-V 2017-21|Honda Sensing|
|
|
|
|
|
+|Honda|CR-V 2017-22|Honda Sensing|
|
|
|
|
|
|Honda|CR-V Hybrid 2017-19|Honda Sensing|
|
|
|
|
|
|Honda|e 2020|All|
|
|
|
|
|
-|Honda|Fit 2018-19|Honda Sensing|
|
|
|
|
|
+|Honda|Fit 2018-20|Honda Sensing|
|
|
|
|
|
|Honda|Freed 2020|Honda Sensing|
|
|
|
|
|
-|Honda|HR-V 2019-20|Honda Sensing|
|
|
|
|
|
-|Honda|Insight 2019-21|All|
|
|
|
|
|
+|Honda|HR-V 2019-22|Honda Sensing|
|
|
|
|
|
+|Honda|Insight 2019-22|All|
|
|
|
|
|
|Honda|Inspire 2018|All|
|
|
|
|
|
-|Honda|Odyssey 2018-20|Honda Sensing|
|
|
|
|
|
+|Honda|Odyssey 2018-22|Honda Sensing|
|
|
|
|
|
|Honda|Passport 2019-21|All|
|
|
|
|
|
-|Honda|Pilot 2016-21|Honda Sensing|
|
|
|
|
|
+|Honda|Pilot 2016-22|Honda Sensing|
|
|
|
|
|
|Honda|Ridgeline 2017-22|Honda Sensing|
|
|
|
|
|
|Hyundai|Elantra 2017-19|SCC + LKAS|
|
|
|
|
|
|Hyundai|Genesis 2015-16|SCC + LKAS|
|
|
|
|
|
@@ -190,16 +198,16 @@ How We Rate The Cars
|Hyundai|Tucson 2021|SCC + LKAS|
|
|
|
|
|
|Hyundai|Veloster 2019-20|SCC + LKAS|
|
|
|
|
|
|Jeep|Grand Cherokee 2016-18|Adaptive Cruise|
|
|
|
|
|
-|Jeep|Grand Cherokee 2019-20|Adaptive Cruise|
|
|
|
|
|
+|Jeep|Grand Cherokee 2019-21|Adaptive Cruise|
|
|
|
|
|
|Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|
|
|
|
|
|
|Kia|Optima 2017|SCC + LKAS|
|
|
|
|
|
|Lexus|IS 2017-19|All|
|
|
|
|
|
-|Lexus|RC 2020|All|
|
|
|
|
|
+|Lexus|RC 2017-2020|All|
|
|
|
|
|
|Lexus|RX 2016-18|All|
[3](#footnotes)|
|
|
|
|
|Lexus|RX Hybrid 2016-19|All|
[3](#footnotes)|
|
|
|
|
|Mazda|CX-5 2022|All|
|
|
|
|
|
-|Mazda|CX-9 2021|All|
|
|
|
|
|
-|Ram|1500 2019-21|Adaptive Cruise|
|
|
|
|
|
+|Mazda|CX-9 2021-22|All|
|
|
|
|
|
+|Ram|1500 2019-22|Adaptive Cruise|
|
|
|
|
|
|Subaru|Crosstrek 2018-19|EyeSight|
|
|
|
|
|
|Subaru|Impreza 2017-19|EyeSight|
|
|
|
|
|
|Subaru|XV 2018-19|EyeSight|
|
|
|
|
|
@@ -219,11 +227,14 @@ How We Rate The Cars
|Toyota|Prius v 2017|TSS-P|
[3](#footnotes)|
|
|
|
|
|Toyota|RAV4 2016-18|TSS-P|
[3](#footnotes)|
|
|
|
|
|Toyota|Sienna 2018-20|All|
[3](#footnotes)|
|
|
|
|
-|Volkswagen|Arteon 2018, 2021[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Arteon 2018-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Arteon eHybrid 2020-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Arteon R 2020-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|
|
|
|
|
|
|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Jetta 2018-21|Driver Assistance|
|
|
|
|
|
-|Volkswagen|Jetta GLI 2021|Driver Assistance|
|
|
|
|
|
+|Volkswagen|CC 2018-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Jetta 2018-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
+|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Driver Assistance|
|
|
|
|
|
|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|
|
|
|
|
|
|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|
|
|
|
|
|
|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|
|
|
|
|
|
@@ -239,6 +250,7 @@ How We Rate The Cars
5Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
6Refers only to the MQB-based European B8 Passat, not including the NMS Passat in the USA/China/Mideast markets.
7Model-years 2021 and beyond may have a new camera harness design, which isn't yet available from the comma store. Before ordering, remove the Lane Assist camera cover and check to see if the connector is black (older design) or light brown (newer design). For the newer design, in the interim, choose "VW J533 Development" from the vehicle drop-down for a harness that integrates at the CAN gateway inside the dashboard.
+8Includes versions with extra rear cargo space (may be called Variant, Estate, SportWagen, Shooting Brake, etc.)
## Community Maintained Cars
Although they're not upstream, the community has openpilot running on other makes and models. See the 'Community Supported Models' section of each make [on our wiki](https://wiki.comma.ai/).
\ No newline at end of file
diff --git a/docs/c_docs.rst b/docs/c_docs.rst
index 5638b40bf0..94d0adb560 100644
--- a/docs/c_docs.rst
+++ b/docs/c_docs.rst
@@ -29,8 +29,6 @@ camerad
^^^^^^^
.. autodoxygenindex::
:project: system_camerad_cameras
-.. autodoxygenindex::
- :project: system_camerad_transforms
.. autodoxygenindex::
:project: system_camerad_imgproc
diff --git a/laika_repo b/laika_repo
index 828612e1b8..3ce2628dfc 160000
--- a/laika_repo
+++ b/laika_repo
@@ -1 +1 @@
-Subproject commit 828612e1b8848ccf70072d5513c0b7977f1707da
+Subproject commit 3ce2628dfc8ddba1769c518f90275e3caca9e8c6
diff --git a/panda b/panda
index 481b505c07..d7a734f54c 160000
--- a/panda
+++ b/panda
@@ -1 +1 @@
-Subproject commit 481b505c07895ace6af471a09df818afbc208931
+Subproject commit d7a734f54c8cced94185864f5f04eda603946f6e
diff --git a/release/files_common b/release/files_common
index 0beb1a3005..1ed1bd6883 100644
--- a/release/files_common
+++ b/release/files_common
@@ -57,6 +57,7 @@ common/api/__init__.py
release/*
+tools/__init__.py
tools/lib/*
tools/joystick/*
tools/replay/*.cc
@@ -128,7 +129,15 @@ system/clocksd/.gitignore
system/clocksd/SConscript
system/clocksd/clocksd.cc
-selfdrive/debug/*.py
+selfdrive/debug/can_printer.py
+selfdrive/debug/check_freq.py
+selfdrive/debug/dump.py
+selfdrive/debug/filter_log_message.py
+selfdrive/debug/get_fingerprint.py
+selfdrive/debug/uiview.py
+
+selfdrive/debug/hyundai_enable_radar_points.py
+selfdrive/debug/vw_mqb_config.py
common/SConscript
common/version.h
@@ -187,6 +196,9 @@ selfdrive/controls/lib/lateral_mpc_lib/*
selfdrive/controls/lib/longitudinal_mpc_lib/*
selfdrive/hardware
+
+system/__init__.py
+
system/hardware/__init__.py
system/hardware/base.h
system/hardware/base.py
@@ -220,6 +232,7 @@ selfdrive/locationd/laikad_helpers.py
selfdrive/locationd/locationd.h
selfdrive/locationd/locationd.cc
selfdrive/locationd/paramsd.py
+selfdrive/locationd/models/__init__.py
selfdrive/locationd/models/.gitignore
selfdrive/locationd/models/car_kf.py
selfdrive/locationd/models/gnss_kf.py
@@ -311,11 +324,6 @@ system/camerad/cameras/camera_common.h
system/camerad/cameras/camera_common.cc
system/camerad/cameras/sensor2_i2c.h
-system/camerad/transforms/rgb_to_yuv.cc
-system/camerad/transforms/rgb_to_yuv.h
-system/camerad/transforms/rgb_to_yuv.cl
-system/camerad/transforms/rgb_to_yuv_test.cc
-
system/camerad/imgproc/conv.cl
system/camerad/imgproc/pool.cl
system/camerad/imgproc/utils.cc
@@ -330,6 +338,7 @@ selfdrive/manager/process.py
selfdrive/manager/test/__init__.py
selfdrive/manager/test/test_manager.py
+selfdrive/modeld/__init__.py
selfdrive/modeld/SConscript
selfdrive/modeld/modeld.cc
selfdrive/modeld/dmonitoringmodeld.cc
diff --git a/selfdrive/assets/navigation/direction_turn_left_inactive.png b/selfdrive/assets/navigation/direction_turn_left_inactive.png
new file mode 100644
index 0000000000..2946984acd
Binary files /dev/null and b/selfdrive/assets/navigation/direction_turn_left_inactive.png differ
diff --git a/selfdrive/assets/navigation/direction_turn_right_inactive.png b/selfdrive/assets/navigation/direction_turn_right_inactive.png
new file mode 100644
index 0000000000..7d327766af
Binary files /dev/null and b/selfdrive/assets/navigation/direction_turn_right_inactive.png differ
diff --git a/selfdrive/assets/navigation/direction_turn_straight_inactive.png b/selfdrive/assets/navigation/direction_turn_straight_inactive.png
new file mode 100644
index 0000000000..4c567966ee
Binary files /dev/null and b/selfdrive/assets/navigation/direction_turn_straight_inactive.png differ
diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py
index b6bdece676..1a9a5f50f3 100644
--- a/selfdrive/car/car_helpers.py
+++ b/selfdrive/car/car_helpers.py
@@ -93,17 +93,17 @@ def fingerprint(logcan, sendcan):
if cached_params is not None and len(cached_params.carFw) > 0 and cached_params.carVin is not VIN_UNKNOWN:
cloudlog.warning("Using cached CarParams")
- vin = cached_params.carVin
+ vin, vin_rx_addr = cached_params.carVin, 0
car_fw = list(cached_params.carFw)
else:
cloudlog.warning("Getting VIN & FW versions")
- _, vin = get_vin(logcan, sendcan, bus)
+ _, vin_rx_addr, vin = get_vin(logcan, sendcan, bus)
ecu_rx_addrs = get_present_ecus(logcan, sendcan)
car_fw = get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs)
exact_fw_match, fw_candidates = match_fw_to_car(car_fw)
else:
- vin = VIN_UNKNOWN
+ vin, vin_rx_addr = VIN_UNKNOWN, 0
exact_fw_match, fw_candidates, car_fw = True, set(), []
if len(vin) != 17:
@@ -166,7 +166,7 @@ def fingerprint(logcan, sendcan):
source = car.CarParams.FingerprintSource.fixed
cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, source=source, fuzzy=not exact_match,
- fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), error=True)
+ fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), vin_rx_addr=vin_rx_addr, error=True)
return car_fingerprint, finger, vin, car_fw, source, exact_match
diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py
index e0eb979e6a..6d158e7cd0 100644
--- a/selfdrive/car/chrysler/carcontroller.py
+++ b/selfdrive/car/chrysler/carcontroller.py
@@ -1,7 +1,8 @@
from opendbc.can.packer import CANPacker
+from common.realtime import DT_CTRL
from selfdrive.car import apply_toyota_steer_torque_limits
from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons
-from selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams
+from selfdrive.car.chrysler.values import CAR, RAM_CARS, CarControllerParams
class CarController:
@@ -13,23 +14,45 @@ class CarController:
self.hud_count = 0
self.last_lkas_falling_edge = 0
- self.lkas_active_prev = False
+ self.lkas_control_bit_prev = False
+ self.last_button_frame = 0
self.packer = CANPacker(dbc_name)
+ self.params = CarControllerParams(CP)
- def update(self, CC, CS, low_speed_alert):
+ def update(self, CC, CS):
can_sends = []
+ # TODO: can we make this more sane? why is it different for all the cars?
+ lkas_control_bit = self.lkas_control_bit_prev
+ if CS.out.vEgo > self.CP.minSteerSpeed:
+ lkas_control_bit = True
+ elif self.CP.carFingerprint in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019):
+ if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0):
+ lkas_control_bit = False
+ elif self.CP.carFingerprint in RAM_CARS:
+ if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5):
+ lkas_control_bit = False
+
# EPS faults if LKAS re-enables too quickly
- lkas_active = CC.latActive and not low_speed_alert and (self.frame - self.last_lkas_falling_edge > 200)
+ lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200)
+ lkas_active = CC.latActive and self.lkas_control_bit_prev
# *** control msgs ***
- das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0
- if CC.cruiseControl.cancel:
- can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True))
- elif CC.enabled and CS.out.cruiseState.standstill:
- can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True))
+ # cruise buttons
+ if (self.frame - self.last_button_frame)*DT_CTRL > 0.05:
+ das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0
+
+ # ACC cancellation
+ if CC.cruiseControl.cancel:
+ self.last_button_frame = self.frame
+ can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True))
+
+ # ACC resume from standstill
+ elif CC.cruiseControl.resume:
+ self.last_button_frame = self.frame
+ can_sends.append(create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True))
# HUD alerts
if self.frame % 25 == 0:
@@ -40,22 +63,22 @@ class CarController:
# steering
if self.frame % 2 == 0:
# steer torque
- new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX))
- apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, CarControllerParams)
+ new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX))
+ apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params)
if not lkas_active:
apply_steer = 0
self.steer_rate_limited = new_steer != apply_steer
self.apply_steer_last = apply_steer
idx = self.frame // 2
- can_sends.append(create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_active, idx))
+ can_sends.append(create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit, idx))
self.frame += 1
- if not lkas_active and self.lkas_active_prev:
+ if not lkas_control_bit and self.lkas_control_bit_prev:
self.last_lkas_falling_edge = self.frame
- self.lkas_active_prev = lkas_active
+ self.lkas_control_bit_prev = lkas_control_bit
new_actuators = CC.actuators.copy()
- new_actuators.steer = self.apply_steer_last / CarControllerParams.STEER_MAX
+ new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX
return new_actuators, can_sends
diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py
index 632c0d2bcf..1e26a6d275 100644
--- a/selfdrive/car/chrysler/chryslercan.py
+++ b/selfdrive/car/chrysler/chryslercan.py
@@ -52,12 +52,12 @@ def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, au
return packer.make_can_msg("DAS_6", 0, values)
-def create_lkas_command(packer, CP, apply_steer, lat_active, frame):
+def create_lkas_command(packer, CP, apply_steer, lkas_control_bit, frame):
# LKAS_COMMAND Lane-keeping signal to turn the wheel
enabled_val = 2 if CP.carFingerprint in RAM_CARS else 1
values = {
"STEERING_TORQUE": apply_steer,
- "LKAS_CONTROL_BIT": enabled_val if lat_active else 0,
+ "LKAS_CONTROL_BIT": enabled_val if lkas_control_bit else 0,
}
return packer.make_can_msg("LKAS_COMMAND", 0, values, frame % 0x10)
diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py
index 697fb9b83a..acc08954a8 100755
--- a/selfdrive/car/chrysler/interface.py
+++ b/selfdrive/car/chrysler/interface.py
@@ -46,15 +46,15 @@ class CarInterface(CarInterfaceBase):
# Ram
elif candidate == CAR.RAM_1500:
+ ret.steerActuatorDelay = 0.2
+
ret.wheelbase = 3.88
ret.steerRatio = 16.3
ret.mass = 2493. + STD_CARGO_KG
ret.maxLateralAccel = 2.4
ret.minSteerSpeed = 14.5
+ CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
- ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[0.], [0.]]
- ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.1], [0.02]]
- ret.lateralTuning.pid.kf = 0.00003
else:
raise ValueError(f"Unsupported car: {candidate}")
@@ -93,4 +93,4 @@ class CarInterface(CarInterfaceBase):
return ret
def apply(self, c):
- return self.CC.update(c, self.CS, self.low_speed_alert)
+ return self.CC.update(c, self.CS)
diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py
index ada4f486fc..80baba9bd6 100644
--- a/selfdrive/car/chrysler/values.py
+++ b/selfdrive/car/chrysler/values.py
@@ -26,10 +26,16 @@ class CAR:
class CarControllerParams:
- STEER_MAX = 261 # higher than this faults the EPS on Chrysler/Jeep. Ram DT allows more
- STEER_DELTA_UP = 3
- STEER_DELTA_DOWN = 3
- STEER_ERROR_MAX = 80
+ def __init__(self, CP):
+ self.STEER_MAX = 261 # higher than this faults the EPS on Chrysler/Jeep. Ram DT allows more
+ self.STEER_ERROR_MAX = 80
+
+ if CP.carFingerprint in RAM_CARS:
+ self.STEER_DELTA_UP = 6
+ self.STEER_DELTA_DOWN = 6
+ else:
+ self.STEER_DELTA_UP = 3
+ self.STEER_DELTA_DOWN = 3
STEER_THRESHOLD = 120
@@ -47,8 +53,8 @@ CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = {
CAR.PACIFICA_2018: ChryslerCarInfo("Chrysler Pacifica 2017-18"),
CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2019-20"),
CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"),
- CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-20", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"),
- CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-21"),
+ CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"),
+ CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-22"),
}
# Unique CAN messages:
diff --git a/selfdrive/car/disable_ecu.py b/selfdrive/car/disable_ecu.py
old mode 100644
new mode 100755
index ac5c6c9f8f..cd3e93fa80
--- a/selfdrive/car/disable_ecu.py
+++ b/selfdrive/car/disable_ecu.py
@@ -6,6 +6,7 @@ EXT_DIAG_RESPONSE = b'\x50\x03'
COM_CONT_RESPONSE = b''
+
def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False):
"""Silence an ECU by disabling sending and receiving messages using UDS 0x28.
The ECU will stay silent as long as openpilot keeps sending Tester Present.
@@ -26,9 +27,22 @@ def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, com_cont_req=b'\x28\x83\x01'
cloudlog.warning("ecu disabled")
return True
+
except Exception:
cloudlog.exception("ecu disable exception")
print(f"ecu disable retry ({i+1}) ...")
cloudlog.warning("ecu disable failed")
return False
+
+
+if __name__ == "__main__":
+ import time
+ import cereal.messaging as messaging
+ sendcan = messaging.pub_sock('sendcan')
+ logcan = messaging.sub_sock('can')
+ time.sleep(1)
+
+ # honda bosch radar disable
+ disabled = disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03', timeout=0.5, debug=False)
+ print(f"disabled: {disabled}")
diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py
index c4b158aebb..c7256e7438 100755
--- a/selfdrive/car/fw_versions.py
+++ b/selfdrive/car/fw_versions.py
@@ -99,6 +99,11 @@ CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x
CHRYSLER_RX_OFFSET = -0x280
+FORD_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
+ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
+FORD_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
+ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
+
@dataclass
class Request:
@@ -207,6 +212,13 @@ REQUESTS: List[Request] = [
[CHRYSLER_VERSION_REQUEST],
[CHRYSLER_VERSION_RESPONSE],
),
+ # Ford
+ Request(
+ "ford",
+ [TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST],
+ [TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE],
+ bus=0,
+ ),
]
@@ -394,7 +406,7 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa
brand_matches = get_brand_ecu_matches(ecu_rx_addrs)
for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True):
- car_fw = get_fw_versions(logcan, sendcan, brand=brand, timeout=timeout, debug=debug, progress=progress)
+ car_fw = get_fw_versions(logcan, sendcan, query_brand=brand, timeout=timeout, debug=debug, progress=progress)
all_car_fw.extend(car_fw)
matches = match_fw_to_car_exact(build_fw_dict(car_fw))
if len(matches) == 1:
@@ -403,10 +415,10 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, debug=Fa
return all_car_fw
-def get_fw_versions(logcan, sendcan, brand=None, extra=None, timeout=0.1, debug=False, progress=False):
+def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, debug=False, progress=False):
versions = get_interface_attr('FW_VERSIONS', ignore_none=True)
- if brand is not None:
- versions = {brand: versions[brand]}
+ if query_brand is not None:
+ versions = {query_brand: versions[query_brand]}
if extra is not None:
versions.update(extra)
@@ -434,7 +446,7 @@ def get_fw_versions(logcan, sendcan, brand=None, extra=None, timeout=0.1, debug=
addrs.insert(0, parallel_addrs)
fw_versions = {}
- requests = [r for r in REQUESTS if brand is None or r.brand == brand]
+ requests = [r for r in REQUESTS if query_brand is None or r.brand == query_brand]
for addr in tqdm(addrs, disable=not progress):
for addr_chunk in chunks(addr):
for r in requests:
@@ -444,7 +456,7 @@ def get_fw_versions(logcan, sendcan, brand=None, extra=None, timeout=0.1, debug=
if addrs:
query = IsoTpParallelQuery(sendcan, logcan, r.bus, addrs, r.request, r.response, r.rx_offset, debug=debug)
- fw_versions.update({(r.brand, addr): (version, r) for addr, version in query.get_data(timeout).items()})
+ fw_versions.update({(r.brand, addr): (version, r) for (addr, _), version in query.get_data(timeout).items()})
except Exception:
cloudlog.warning(f"FW query exception: {traceback.format_exc()}")
@@ -497,13 +509,13 @@ if __name__ == "__main__":
t = time.time()
print("Getting vin...")
- addr, vin = get_vin(logcan, sendcan, 1, retry=10, debug=args.debug)
- print(f"VIN: {vin}")
+ addr, vin_rx_addr, vin = get_vin(logcan, sendcan, 1, retry=10, debug=args.debug)
+ print(f'TX: {hex(addr)}, RX: {hex(vin_rx_addr)}, VIN: {vin}')
print(f"Getting VIN took {time.time() - t:.3f} s")
print()
t = time.time()
- fw_vers = get_fw_versions(logcan, sendcan, brand=args.brand, extra=extra, debug=args.debug, progress=True)
+ fw_vers = get_fw_versions(logcan, sendcan, query_brand=args.brand, extra=extra, debug=args.debug, progress=True)
_, candidates = match_fw_to_car(fw_vers)
print()
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index c6e20f2d83..c665b1cd03 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -109,13 +109,13 @@ class HondaCarInfo(CarInfo):
CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = {
CAR.ACCORD: [
- HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
+ HondaCarInfo("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
],
- CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "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_BOSCH: [
- HondaCarInfo("Honda Civic 2019-20", "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 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),
],
CAR.CIVIC_BOSCH_DIESEL: None, # same platform
@@ -125,20 +125,20 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = {
],
CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring", harness=Harness.nidec),
- CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21", harness=Harness.bosch_a),
+ CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-22", harness=Harness.bosch_a),
CAR.CRV_EU: None, # HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring
CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", harness=Harness.bosch_a),
- CAR.FIT: HondaCarInfo("Honda Fit 2018-19", harness=Harness.nidec),
+ CAR.FIT: HondaCarInfo("Honda Fit 2018-20", harness=Harness.nidec),
CAR.FREED: HondaCarInfo("Honda Freed 2020", harness=Harness.nidec),
- CAR.HRV: HondaCarInfo("Honda HR-V 2019-20", harness=Harness.nidec),
- CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", min_steer_speed=0., harness=Harness.nidec),
+ CAR.HRV: HondaCarInfo("Honda HR-V 2019-22", harness=Harness.nidec),
+ CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-22", min_steer_speed=0., harness=Harness.nidec),
CAR.ODYSSEY_CHN: None, # Chinese version of Odyssey
CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus", harness=Harness.nidec),
- CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
- CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21", harness=Harness.nidec),
+ CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
+ CAR.PILOT: HondaCarInfo("Honda Pilot 2016-22", harness=Harness.nidec),
CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All", harness=Harness.nidec),
CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22", harness=Harness.nidec),
- CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
+ CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
}
@@ -1406,6 +1406,7 @@ FW_VERSIONS = {
b'38897-T20-A020\x00\x00',
b'38897-T20-A510\x00\x00',
b'38897-T21-A010\x00\x00',
+ b'38897-T20-A210\x00\x00',
],
(Ecu.srs, 0x18DA53F1, None): [
b'77959-T20-A970\x00\x00',
@@ -1415,6 +1416,7 @@ FW_VERSIONS = {
b'78108-T21-A220\x00\x00',
b'78108-T21-A620\x00\x00',
b'78108-T23-A110\x00\x00',
+ b'78108-T21-A230\x00\x00',
],
(Ecu.vsa, 0x18DA28F1, None): [
b'57114-T20-AB40\x00\x00',
@@ -1429,6 +1431,7 @@ FW_VERSIONS = {
b'37805-64L-A540\x00\x00',
b'37805-64S-A540\x00\x00',
b'37805-64S-A720\x00\x00',
+ b'37805-64A-A540\x00\x00',
],
},
}
diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py
index a878ad3274..d0d9c40839 100644
--- a/selfdrive/car/hyundai/carcontroller.py
+++ b/selfdrive/car/hyundai/carcontroller.py
@@ -82,12 +82,12 @@ class CarController:
if (self.frame - self.last_button_frame) * DT_CTRL > 0.25:
if CC.cruiseControl.cancel:
for _ in range(20):
- can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, True, False))
+ can_sends.append(hda2can.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(hda2can.create_buttons(self.packer, CS.buttons_counter+1, False, True))
+ can_sends.append(hda2can.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL))
self.last_button_frame = self.frame
else:
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index a10cdadbca..8afd851f00 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -8,7 +8,7 @@ from opendbc.can.can_define import CANDefine
from selfdrive.car.hyundai.values import DBC, FEATURES, HDA2_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams
from selfdrive.car.interfaces import CarStateBase
-PREV_BUTTON_SAMPLES = 4
+PREV_BUTTON_SAMPLES = 8
class CarState(CarStateBase):
@@ -171,7 +171,10 @@ class CarState(CarStateBase):
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
- self.buttons_counter = cp.vl["CRUISE_BUTTONS"]["_COUNTER"]
+ 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"]
+
self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"])
return ret
@@ -362,7 +365,9 @@ class CarState(CarStateBase):
("CRUISE_ACTIVE", "SCC1"),
("SET_SPEED", "CRUISE_INFO"),
("CRUISE_STANDSTILL", "CRUISE_INFO"),
- ("_COUNTER", "CRUISE_BUTTONS"),
+ ("COUNTER", "CRUISE_BUTTONS"),
+ ("CRUISE_BUTTONS", "CRUISE_BUTTONS"),
+ ("ADAPTIVE_CRUISE_MAIN_BTN", "CRUISE_BUTTONS"),
("DISTANCE_UNIT", "CLUSTER_INFO"),
diff --git a/selfdrive/car/hyundai/hda2can.py b/selfdrive/car/hyundai/hda2can.py
index 437f5cf538..9a9e477cf5 100644
--- a/selfdrive/car/hyundai/hda2can.py
+++ b/selfdrive/car/hyundai/hda2can.py
@@ -18,11 +18,9 @@ def create_cam_0x2a4(packer, frame, camera_values):
})
return packer.make_can_msg("CAM_0x2a4", 4, camera_values, frame % 255)
-def create_buttons(packer, cnt, cancel, resume):
+def create_buttons(packer, cnt, btn):
values = {
- "_COUNTER": cnt % 0xf,
"SET_ME_1": 1,
- "DISTANCE_BTN": 1 if resume else 0,
- "PAUSE_RESUME_BTN": 1 if cancel else 0,
+ "CRUISE_BUTTONS": btn,
}
- return packer.make_can_msg("CRUISE_BUTTONS", 5, values)
+ return packer.make_can_msg("CRUISE_BUTTONS", 5, values, cnt % 0xf)
diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py
index 069b0e74e5..a32ee2c0ab 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, HDA2_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams
+from selfdrive.car.hyundai.values import CAR, DBC, 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_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config
from selfdrive.car.interfaces import CarInterfaceBase
@@ -321,8 +321,7 @@ class CarInterface(CarInterfaceBase):
# To avoid re-engaging when openpilot cancels, check user engagement intention via buttons
# Main button also can trigger an engagement on these cars
allow_enable = any(btn in ENABLE_BUTTONS for btn in self.CS.cruise_buttons) or any(self.CS.main_buttons)
- allow_enable = allow_enable or self.CP.carFingerprint in HDA2_CAR
- events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable or True)
+ events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable)
if self.CS.brake_error:
events.add(EventName.brakeUnavailable)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 4b3acf3f27..ffa29c60d4 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -151,15 +151,15 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Kia Sorento 2018", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c),
HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e),
],
- CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c),
+ CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c),
CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e),
CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "All", harness=Harness.hyundai_p),
# Genesis
- CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018", "All", harness=Harness.hyundai_f),
+ CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018-19", "All", harness=Harness.hyundai_f),
CAR.GENESIS_G70_2020: HyundaiCarInfo("Genesis G70 2020", "All", harness=Harness.hyundai_f),
- CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2018", "All", harness=Harness.hyundai_h),
- CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2018", "All", harness=Harness.hyundai_c),
+ CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2017-19", "All", harness=Harness.hyundai_h),
+ CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2017-18", "All", harness=Harness.hyundai_c),
}
class Buttons:
@@ -167,7 +167,7 @@ class Buttons:
RES_ACCEL = 1
SET_DECEL = 2
GAP_DIST = 3
- CANCEL = 4
+ CANCEL = 4 # on newer models, this is a pause/resume button
FINGERPRINTS = {
CAR.ELANTRA: [{
diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py
index 136337c5a4..4c7ea97dff 100644
--- a/selfdrive/car/interfaces.py
+++ b/selfdrive/car/interfaces.py
@@ -135,11 +135,11 @@ class CarInterfaceBase(ABC):
return ret
@staticmethod
- def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0):
+ def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0, use_steering_angle=True):
params = get_torque_params(candidate)
tune.init('torque')
- tune.torque.useSteeringAngle = True
+ tune.torque.useSteeringAngle = use_steering_angle
tune.torque.kp = 1.0 / params['LAT_ACCEL_FACTOR']
tune.torque.kf = 1.0 / params['LAT_ACCEL_FACTOR']
tune.torque.ki = 0.1 / params['LAT_ACCEL_FACTOR']
diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py
index 0e807512cf..bb96572c33 100644
--- a/selfdrive/car/isotp_parallel_query.py
+++ b/selfdrive/car/isotp_parallel_query.py
@@ -126,7 +126,7 @@ class IsoTpParallelQuery:
msg.send(self.request[counter + 1])
request_counter[tx_addr] += 1
else:
- results[tx_addr] = dat[len(expected_response):]
+ results[(tx_addr, msg._can_client.rx_addr)] = dat[len(expected_response):]
request_done[tx_addr] = True
else:
error_code = dat[2] if len(dat) > 2 else -1
diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py
index 09b9b7732b..e1d6907991 100644
--- a/selfdrive/car/mazda/values.py
+++ b/selfdrive/car/mazda/values.py
@@ -40,7 +40,7 @@ CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = {
CAR.CX9: MazdaCarInfo("Mazda CX-9 2016-17"),
CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017"),
CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017"),
- CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021"),
+ CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22"),
CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"),
}
@@ -65,6 +65,7 @@ FW_VERSIONS = {
],
(Ecu.engine, 0x7e0, None): [
b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x764, None): [
@@ -266,6 +267,7 @@ FW_VERSIONS = {
(Ecu.engine, 0x7e0, None): [
b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x764, None): [
b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -278,9 +280,11 @@ FW_VERSIONS = {
b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.transmission, 0x7e1, None): [
b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
}
}
diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py
index ea923b1b50..8fac934285 100644
--- a/selfdrive/car/subaru/values.py
+++ b/selfdrive/car/subaru/values.py
@@ -41,18 +41,18 @@ class SubaruCarInfo(CarInfo):
CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = {
- CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20", "All"),
+ CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-21", "All"),
CAR.IMPREZA: [
SubaruCarInfo("Subaru Impreza 2017-19"),
SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"),
SubaruCarInfo("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"),
],
CAR.IMPREZA_2020: [
- SubaruCarInfo("Subaru Impreza 2020-21"),
+ SubaruCarInfo("Subaru Impreza 2020-22"),
SubaruCarInfo("Subaru Crosstrek 2020-21"),
SubaruCarInfo("Subaru XV 2020-21"),
],
- CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-21", "All"),
+ CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-22", "All"),
CAR.FORESTER_PREGLOBAL: SubaruCarInfo("Subaru Forester 2017-18"),
CAR.LEGACY_PREGLOBAL: SubaruCarInfo("Subaru Legacy 2015-18"),
CAR.OUTBACK_PREGLOBAL: SubaruCarInfo("Subaru Outback 2015-17"),
diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml
index 476313df2b..8e6f62c4e7 100644
--- a/selfdrive/car/torque_data/override.yaml
+++ b/selfdrive/car/torque_data/override.yaml
@@ -21,7 +21,7 @@ COMMA BODY: [.nan, 1000, .nan]
# Totally new cars
KIA EV6 2022: [3.5, 2.5, 0.0]
-RAM 1500 5TH GEN: [2.0, 2.0, 0.05]
+RAM 1500 5TH GEN: [2.0, 2.0, 0.0]
# Dashcam or fallback configured as ideal car
mock: [10.0, 10, 0.0]
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index 33e3fe118e..61a41b9c51 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -126,7 +126,7 @@ class CarController:
# forcing the pcm to disengage causes a bad fault sound so play a good sound instead
send_ui = True
- if self.frame % 100 == 0 or send_ui:
+ if (self.frame % 100 == 0 or send_ui) and (self.CP.carFingerprint != CAR.PRIUS_V):
can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible,
hud_control.rightLaneVisible, hud_control.leftLaneDepart,
hud_control.rightLaneDepart, CC.enabled))
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 2a03999342..49aa3c9a94 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -119,12 +119,13 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
CAR.COROLLA: ToyotaCarInfo("Toyota Corolla 2017-19", footnotes=[Footnote.DSU]),
CAR.COROLLA_TSS2: [
ToyotaCarInfo("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"),
- ToyotaCarInfo("Toyota Corolla Cross 2020-21 (Non-US only)"),
+ ToyotaCarInfo("Toyota Corolla Cross 2020-21 (Non-US only)", min_enable_speed=7.5),
ToyotaCarInfo("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"),
],
CAR.COROLLAH_TSS2: [
ToyotaCarInfo("Toyota Corolla Hybrid 2020-22"),
- ToyotaCarInfo("Lexus UX Hybrid 2019-21"),
+ ToyotaCarInfo("Toyota Corolla Cross Hybrid 2020-22 (Non-US only)", min_enable_speed=7.5),
+ ToyotaCarInfo("Lexus UX Hybrid 2019-22"),
],
CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo", footnotes=[Footnote.DSU]),
CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-22"),
@@ -151,14 +152,14 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
# Lexus
CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]),
CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]),
- CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-21"),
+ CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-22"),
CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22", video_link="https://youtu.be/BZ29osRVJeg?t=12"),
CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"),
CAR.LEXUS_NX: ToyotaCarInfo("Lexus NX 2018-19", footnotes=[Footnote.DSU]),
CAR.LEXUS_NXH: ToyotaCarInfo("Lexus NX Hybrid 2018-19", footnotes=[Footnote.DSU]),
- CAR.LEXUS_NX_TSS2: ToyotaCarInfo("Lexus NX 2020"),
- CAR.LEXUS_NXH_TSS2: ToyotaCarInfo("Lexus NX Hybrid 2020"),
- CAR.LEXUS_RC: ToyotaCarInfo("Lexus RC 2020"),
+ CAR.LEXUS_NX_TSS2: ToyotaCarInfo("Lexus NX 2020-21"),
+ CAR.LEXUS_NXH_TSS2: ToyotaCarInfo("Lexus NX Hybrid 2020-21"),
+ CAR.LEXUS_RC: ToyotaCarInfo("Lexus RC 2017-2020"),
CAR.LEXUS_RX: ToyotaCarInfo("Lexus RX 2016-18", footnotes=[Footnote.DSU]),
CAR.LEXUS_RXH: ToyotaCarInfo("Lexus RX Hybrid 2016-19", footnotes=[Footnote.DSU]),
CAR.LEXUS_RX_TSS2: ToyotaCarInfo("Lexus RX 2020-22"),
@@ -788,6 +789,7 @@ FW_VERSIONS = {
(Ecu.eps, 0x7a1, None): [
b'8965B12361\x00\x00\x00\x00\x00\x00',
b'8965B12451\x00\x00\x00\x00\x00\x00',
+ b'8965B16011\x00\x00\x00\x00\x00\x00',
b'8965B76012\x00\x00\x00\x00\x00\x00',
b'8965B76050\x00\x00\x00\x00\x00\x00',
b'\x018965B12350\x00\x00\x00\x00\x00\x00',
@@ -808,15 +810,16 @@ FW_VERSIONS = {
b'F152612800\x00\x00\x00\x00\x00\x00',
b'F152612820\x00\x00\x00\x00\x00\x00',
b'F152612840\x00\x00\x00\x00\x00\x00',
+ b'F152612842\x00\x00\x00\x00\x00\x00',
b'F152612890\x00\x00\x00\x00\x00\x00',
b'F152612A00\x00\x00\x00\x00\x00\x00',
b'F152612A10\x00\x00\x00\x00\x00\x00',
+ b'F152612D00\x00\x00\x00\x00\x00\x00',
+ b'F152616011\x00\x00\x00\x00\x00\x00',
b'F152642540\x00\x00\x00\x00\x00\x00',
b'F152676293\x00\x00\x00\x00\x00\x00',
b'F152676303\x00\x00\x00\x00\x00\x00',
b'F152676304\x00\x00\x00\x00\x00\x00',
- b'F152612D00\x00\x00\x00\x00\x00\x00',
- b'F152612842\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F3301100\x00\x00\x00\x00',
@@ -832,6 +835,7 @@ FW_VERSIONS = {
b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00',
+ b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b"\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00",
b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
@@ -1302,6 +1306,7 @@ FW_VERSIONS = {
b'\x01896634AA0000\x00\x00\x00\x00',
b'\x01896634AA1000\x00\x00\x00\x00',
b'\x01896634A88000\x00\x00\x00\x00',
+ b'\x01896634A89000\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F0R01100\x00\x00\x00\x00',
@@ -1381,11 +1386,12 @@ FW_VERSIONS = {
b'8965B42172\x00\x00\x00\x00\x00\x00',
],
(Ecu.engine, 0x700, None): [
- b'\x01896634A62000\x00\x00\x00\x00',
- b'\x01896634A08000\x00\x00\x00\x00',
- b'\x01896634A61000\x00\x00\x00\x00',
b'\x01896634A02001\x00\x00\x00\x00',
b'\x01896634A03000\x00\x00\x00\x00',
+ b'\x01896634A08000\x00\x00\x00\x00',
+ b'\x01896634A61000\x00\x00\x00\x00',
+ b'\x01896634A62000\x00\x00\x00\x00',
+ b'\x01896634A63000\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F0R01100\x00\x00\x00\x00',
diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py
index fd1ca61e66..007c10e772 100755
--- a/selfdrive/car/vin.py
+++ b/selfdrive/car/vin.py
@@ -22,18 +22,18 @@ def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False):
for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)):
try:
query = IsoTpParallelQuery(sendcan, logcan, bus, FUNCTIONAL_ADDRS, [request, ], [response, ], functional_addr=True, debug=debug)
- for addr, vin in query.get_data(timeout).items():
+ for (addr, rx_addr), vin in query.get_data(timeout).items():
# Honda Bosch response starts with a length, trim to correct length
if vin.startswith(b'\x11'):
vin = vin[1:18]
- return addr[0], vin.decode()
+ return addr[0], rx_addr, vin.decode()
print(f"vin query retry ({i+1}) ...")
except Exception:
cloudlog.warning(f"VIN query exception: {traceback.format_exc()}")
- return 0, VIN_UNKNOWN
+ return 0, 0, VIN_UNKNOWN
if __name__ == "__main__":
@@ -41,5 +41,5 @@ if __name__ == "__main__":
sendcan = messaging.pub_sock('sendcan')
logcan = messaging.sub_sock('can')
time.sleep(1)
- addr, vin = get_vin(logcan, sendcan, 1, debug=False)
- print(hex(addr), vin)
+ addr, vin_rx_addr, vin = get_vin(logcan, sendcan, 1, debug=False)
+ print(f'TX: {hex(addr)}, RX: {hex(vin_rx_addr)}, VIN: {vin}')
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index 346851fcc6..8e568fc649 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -37,6 +37,7 @@ class CANBUS:
pt = 0
cam = 2
+
class DBC_FILES:
mqb = "vw_mqb_2010" # Used for all cars with MQB-style CAN messaging
pq = "vw_golf_mk4" # Used for all cars with PQ-style (legacy) CAN messaging
@@ -124,6 +125,9 @@ class Footnote(Enum):
"(older design) or light brown (newer design). For the newer design, in the interim, choose \"VW J533 Development\" " +
"from the vehicle drop-down for a harness that integrates at the CAN gateway inside the dashboard.",
Column.MODEL)
+ VW_VARIANT = CarFootnote(
+ "Includes versions with extra rear cargo space (may be called Variant, Estate, SportWagen, Shooting Brake, etc.)",
+ Column.MODEL)
@dataclass
@@ -133,25 +137,43 @@ class VWCarInfo(CarInfo):
CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
- CAR.ARTEON_MK1: VWCarInfo("Volkswagen Arteon 2018, 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
- CAR.ATLAS_MK1: VWCarInfo("Volkswagen Atlas 2018-19, 2022", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ CAR.ARTEON_MK1: [
+ VWCarInfo("Volkswagen Arteon 2018-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533),
+ VWCarInfo("Volkswagen Arteon R 2020-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533),
+ VWCarInfo("Volkswagen Arteon eHybrid 2020-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533),
+ VWCarInfo("Volkswagen CC 2018-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533),
+ ],
+ CAR.ATLAS_MK1: [
+ VWCarInfo("Volkswagen Atlas 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Atlas Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Teramont 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Teramont Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Teramont X 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ ],
CAR.GOLF_MK7: [
- VWCarInfo("Volkswagen e-Golf 2014, 2018-20"),
- VWCarInfo("Volkswagen Golf 2015-20"),
- VWCarInfo("Volkswagen Golf Alltrack 2017-18"),
- VWCarInfo("Volkswagen Golf GTE 2016"),
- VWCarInfo("Volkswagen Golf GTI 2018-21"),
- VWCarInfo("Volkswagen Golf R 2016-19"),
- VWCarInfo("Volkswagen Golf SportsVan 2016"),
- VWCarInfo("Volkswagen Golf SportWagen 2015"),
+ VWCarInfo("Volkswagen e-Golf 2014-20"),
+ VWCarInfo("Volkswagen Golf 2015-20", footnotes=[Footnote.VW_VARIANT]),
+ VWCarInfo("Volkswagen Golf Alltrack 2015-19"),
+ VWCarInfo("Volkswagen Golf GTD 2015-20"),
+ VWCarInfo("Volkswagen Golf GTE 2015-20"),
+ VWCarInfo("Volkswagen Golf GTI 2015-21"),
+ VWCarInfo("Volkswagen Golf R 2015-19", footnotes=[Footnote.VW_VARIANT]),
+ VWCarInfo("Volkswagen Golf SportsVan 2015-20"),
],
CAR.JETTA_MK7: [
- VWCarInfo("Volkswagen Jetta 2018-21"),
- VWCarInfo("Volkswagen Jetta GLI 2021"),
+ VWCarInfo("Volkswagen Jetta 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Jetta GLI 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ ],
+ CAR.PASSAT_MK8: [
+ VWCarInfo("Volkswagen Passat 2015-22", footnotes=[Footnote.VW_HARNESS, Footnote.PASSAT, Footnote.VW_VARIANT], harness=Harness.j533),
+ VWCarInfo("Volkswagen Passat Alltrack 2015-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Passat GTE 2015-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533),
],
- CAR.PASSAT_MK8: VWCarInfo("Volkswagen Passat 2015-19", footnotes=[Footnote.PASSAT]),
CAR.PASSAT_NMS: VWCarInfo("Volkswagen Passat NMS 2017, 2021"),
- CAR.POLO_MK6: VWCarInfo("Volkswagen Polo 2020"),
+ CAR.POLO_MK6: [
+ VWCarInfo("Volkswagen Polo 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ VWCarInfo("Volkswagen Polo GTI 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
+ ],
CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 117509f1e6..a20a3a9f37 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -96,7 +96,11 @@ class Controls:
self.sm = sm
if self.sm is None:
- ignore = ['driverCameraState', 'managerState'] if SIMULATION else None
+ ignore = []
+ if SIMULATION:
+ ignore += ['driverCameraState', 'managerState']
+ if params.get_bool('WideCameraOnly'):
+ ignore += ['roadCameraState']
self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration',
'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman',
'managerState', 'liveParameters', 'radarState'] + self.camera_packets + joystick_packet,
@@ -224,12 +228,8 @@ class Controls:
if not self.CP.notCar:
self.events.add_from_msg(self.sm['driverMonitoringState'].events)
- # Handle car events. Ignore when CAN is invalid
- if CS.canTimeout:
- self.events.add(EventName.canBusMissing)
- elif not CS.canValid:
- self.events.add(EventName.canError)
- else:
+ # Add car events, ignore if CAN isn't valid
+ if CS.canValid:
self.events.add_from_msg(CS.events)
# Create events for temperature, disk space, and memory
@@ -309,14 +309,19 @@ class Controls:
self.events.add(EventName.cameraFrameRate)
if self.rk.lagging:
self.events.add(EventName.controlsdLagging)
- if len(self.sm['radarState'].radarErrors):
+ if len(self.sm['radarState'].radarErrors) or not self.sm.all_checks(['radarState']):
self.events.add(EventName.radarFault)
if not self.sm.valid['pandaStates']:
self.events.add(EventName.usbError)
+ if CS.canTimeout:
+ self.events.add(EventName.canBusMissing)
+ elif not CS.canValid:
+ self.events.add(EventName.canError)
# generic catch-all. ideally, a more specific event should be added above instead
- no_system_errors = len(self.events) != num_events
- if (not self.sm.all_checks() or self.can_rcv_error) and no_system_errors and CS.canValid and not CS.canTimeout:
+ has_disable_events = self.events.any(ET.NO_ENTRY) and (self.events.any(ET.SOFT_DISABLE) or self.events.any(ET.IMMEDIATE_DISABLE))
+ no_system_errors = (not has_disable_events) or (len(self.events) == num_events)
+ if (not self.sm.all_checks() or self.can_rcv_error) and no_system_errors:
if not self.sm.all_alive():
self.events.add(EventName.commIssue)
elif not self.sm.all_freq_ok():
@@ -406,7 +411,8 @@ class Controls:
if not self.initialized:
all_valid = CS.canValid and self.sm.all_checks()
- if all_valid or self.sm.frame * DT_CTRL > 3.5 or SIMULATION:
+ timed_out = self.sm.frame * DT_CTRL > (6. if REPLAY else 3.5)
+ if all_valid or timed_out or SIMULATION:
if not self.read_only:
self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan'])
self.initialized = True
diff --git a/selfdrive/debug/disable_ecu.py b/selfdrive/debug/disable_ecu.py
deleted file mode 100644
index af007207eb..0000000000
--- a/selfdrive/debug/disable_ecu.py
+++ /dev/null
@@ -1,40 +0,0 @@
-#!/usr/bin/env python3
-import traceback
-
-import cereal.messaging as messaging
-from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery
-from system.swaglog import cloudlog
-
-EXT_DIAG_REQUEST = b'\x10\x03'
-EXT_DIAG_RESPONSE = b'\x50\x03'
-COM_CONT_REQUEST = b'\x28\x83\x03'
-COM_CONT_RESPONSE = b''
-
-def disable_ecu(ecu_addr, logcan, sendcan, bus, timeout=0.5, retry=5, debug=False):
- print(f"ecu disable {hex(ecu_addr)} ...")
- for i in range(retry):
- try:
- # enter extended diagnostic session
- query = IsoTpParallelQuery(sendcan, logcan, bus, [ecu_addr], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug)
- for addr, dat in query.get_data(timeout).items(): # pylint: disable=unused-variable
- print("ecu communication control disable tx/rx ...")
- # communication control disable tx and rx
- query = IsoTpParallelQuery(sendcan, logcan, bus, [ecu_addr], [COM_CONT_REQUEST], [COM_CONT_RESPONSE], debug=debug)
- query.get_data(0)
- return True
- print(f"ecu disable retry ({i+1}) ...")
- except Exception:
- cloudlog.warning(f"ecu disable exception: {traceback.format_exc()}")
-
- return False
-
-
-if __name__ == "__main__":
- import time
- sendcan = messaging.pub_sock('sendcan')
- logcan = messaging.sub_sock('can')
- time.sleep(1)
-
- # honda bosch radar disable
- disabled = disable_ecu(0x18DAB0F1, logcan, sendcan, 1, debug=False)
- print(f"disabled: {disabled}")
diff --git a/selfdrive/debug/dump_car_info.py b/selfdrive/debug/dump_car_info.py
new file mode 100755
index 0000000000..c9a21c2848
--- /dev/null
+++ b/selfdrive/debug/dump_car_info.py
@@ -0,0 +1,18 @@
+#!/usr/bin/env python3
+import argparse
+import pickle
+
+from selfdrive.car.docs import get_all_car_info
+
+
+def dump_car_info(path):
+ with open(path, 'wb') as f:
+ pickle.dump(get_all_car_info(), f)
+ print(f'Dumping car info to {path}')
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser()
+ parser.add_argument("--path", required=True)
+ args = parser.parse_args()
+ dump_car_info(args.path)
diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py
new file mode 100755
index 0000000000..5cf3867b2d
--- /dev/null
+++ b/selfdrive/debug/print_docs_diff.py
@@ -0,0 +1,90 @@
+#!/usr/bin/env python3
+import argparse
+import pickle
+
+from selfdrive.car.docs import get_all_car_info
+from selfdrive.car.docs_definitions import Column
+
+STAR_ICON = ''
+COLUMNS = "|" + "|".join([column.value for column in Column]) + "|"
+COLUMN_HEADER = "|---|---|---|:---:|:---:|:---:|:---:|:---:|"
+ARROW_SYMBOL = "➡️"
+
+
+def load_base_car_info(path):
+ with open(path, "rb") as f:
+ return pickle.load(f)
+
+
+def get_star_diff(base_car, new_car):
+ return [column for column, value in base_car.row.items() if value != new_car.row[column]]
+
+
+def format_row(builder):
+ return "|" + "|".join(builder) + "|"
+
+
+def print_car_info_diff(path):
+ base_car_info = {f"{i.make} {i.model}": i for i in load_base_car_info(path)}
+ new_car_info = {f"{i.make} {i.model}": i for i in get_all_car_info()}
+
+ tier_changes = []
+ star_changes = []
+ removals = []
+ additions = []
+
+ # Changes (tier + stars)
+ for base_car_model, base_car in base_car_info.items():
+ if base_car_model not in new_car_info:
+ continue
+
+ new_car = new_car_info[base_car_model]
+
+ # Tier changes
+ if base_car.tier != new_car.tier:
+ tier_changes.append(f"- Tier for {base_car.make} {base_car.model} changed! ({base_car.tier.name.title()} {ARROW_SYMBOL} {new_car.tier.name.title()})")
+
+ # Star changes
+ diff = get_star_diff(base_car, new_car)
+ if not len(diff):
+ continue
+
+ row_builder = []
+ for column in list(Column):
+ if column not in diff:
+ row_builder.append(new_car.get_column(column, STAR_ICON, "{}"))
+ else:
+ row_builder.append(base_car.get_column(column, STAR_ICON, "{}") + ARROW_SYMBOL + new_car.get_column(column, STAR_ICON, "{}"))
+
+ star_changes.append(format_row(row_builder))
+
+ # Removals
+ for model in set(base_car_info) - set(new_car_info):
+ car_info = base_car_info[model]
+ removals.append(format_row([car_info.get_column(column, STAR_ICON, "{}") for column in Column]))
+
+ # Additions
+ for model in set(new_car_info) - set(base_car_info):
+ car_info = new_car_info[model]
+ additions.append(format_row([car_info.get_column(column, STAR_ICON, "{}") for column in Column]))
+
+ # Print diff
+ if len(star_changes) or len(tier_changes) or len(removals) or len(additions):
+ markdown_builder = ["### ⚠️ This PR makes changes to [CARS.md](../blob/master/docs/CARS.md) ⚠️"]
+
+ for title, category in (("## 🏅 Tier Changes", tier_changes), ("## 🔀 Star Changes", star_changes), ("## ❌ Removed", removals), ("## ➕ Added", additions)):
+ if len(category):
+ markdown_builder.append(title)
+ if "Tier" not in title:
+ markdown_builder.append(COLUMNS)
+ markdown_builder.append(COLUMN_HEADER)
+ markdown_builder.extend(category)
+
+ print("\n".join(markdown_builder))
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser()
+ parser.add_argument("--path", required=True)
+ args = parser.parse_args()
+ print_car_info_diff(args.path)
diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py
index 0954cb4c9f..b67c483497 100755
--- a/selfdrive/locationd/laikad.py
+++ b/selfdrive/locationd/laikad.py
@@ -15,6 +15,7 @@ from cereal import log, messaging
from common.params import Params, put_nonblocking
from laika import AstroDog
from laika.constants import SECS_IN_HR, SECS_IN_MIN
+from laika.downloader import DownloadFailed
from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem
from laika.gps_time import GPSTime
from laika.helpers import ConstellationId
@@ -27,6 +28,7 @@ from system.swaglog import cloudlog
MAX_TIME_GAP = 10
EPHEMERIS_CACHE = 'LaikadEphemeris'
+DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache"
CACHE_VERSION = 0.1
POS_FIX_RESIDUAL_THRESHOLD = 100.0
@@ -42,7 +44,7 @@ class Laikad:
valid_ephem_types: Valid ephemeris types to be used by AstroDog
save_ephemeris: If true saves and loads nav and orbit ephemeris to cache.
"""
- self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True)
+ self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True, cache_dir=DOWNLOADS_CACHE_FOLDER)
self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True)
self.auto_fetch_orbits = auto_fetch_orbits
@@ -77,8 +79,8 @@ class Laikad:
cloudlog.exception("Error parsing cache")
timestamp = self.last_fetch_orbits_t.as_datetime() if self.last_fetch_orbits_t is not None else 'Nan'
cloudlog.debug(
- f"Loaded nav and orbits cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['orbits'].keys())} {list(cache['nav'].keys())} " +
- f"Total: {sum([len(v) for v in cache['orbits']])} and {sum([len(v) for v in cache['nav']])}")
+ f"Loaded nav ({sum([len(v) for v in cache['nav']])}) and orbits ({sum([len(v) for v in cache['orbits']])}) cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['orbits'].keys())} {list(cache['nav'].keys())} " +
+ f"With time range: {[f'{start.as_datetime()}, {end.as_datetime()}' for (start,end) in self.astro_dog.orbit_fetched_times._ranges]}")
def cache_ephemeris(self, t: GPSTime):
if self.save_ephemeris and (self.last_cached_t is None or t - self.last_cached_t > SECS_IN_MIN):
@@ -92,10 +94,15 @@ class Laikad:
if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2:
min_measurements = 6 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 5
pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements)
- if len(pos_fix) > 0 and np.median(np.abs(pos_fix_residual)) < POS_FIX_RESIDUAL_THRESHOLD:
- self.last_pos_fix = pos_fix[:3]
- self.last_pos_residual = pos_fix_residual
+ if len(pos_fix) > 0:
self.last_pos_fix_t = t
+ residual_median = np.median(np.abs(pos_fix_residual))
+ if np.median(np.abs(pos_fix_residual)) < POS_FIX_RESIDUAL_THRESHOLD:
+ cloudlog.debug(f"Pos fix is within threshold with median: {residual_median.round()}")
+ self.last_pos_fix = pos_fix[:3]
+ self.last_pos_residual = pos_fix_residual
+ else:
+ cloudlog.debug(f"Pos fix failed with median: {residual_median.round()}. All residuals: {np.round(pos_fix_residual)}")
return self.last_pos_fix
def process_ublox_msg(self, ublox_msg, ublox_mono_time: int, block=False):
@@ -113,10 +120,11 @@ class Laikad:
new_meas = [m for m in new_meas if 1e7 < m.observables['C1C'] < 3e7]
processed_measurements = process_measurements(new_meas, self.astro_dog)
-
est_pos = self.get_est_pos(t, processed_measurements)
corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) if len(est_pos) > 0 else []
+ if ublox_mono_time % 10 == 0:
+ cloudlog.debug(f"Measurements Incoming/Processed/Corrected: {len(new_meas), len(processed_measurements), len(corrected_measurements)}")
self.update_localizer(est_pos, t, corrected_measurements)
kf_valid = all(self.kf_valid(t))
@@ -183,7 +191,7 @@ class Laikad:
def fetch_orbits(self, t: GPSTime, block):
# Download new orbits if 1 hour of orbits data left
if t + SECS_IN_HR not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or abs(t - self.last_fetch_orbits_t) > SECS_IN_MIN):
- astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types
+ astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types, self.astro_dog.cache_dir
ret = None
if block: # Used for testing purposes
@@ -203,15 +211,17 @@ class Laikad:
self.cache_ephemeris(t=t)
-def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types):
- astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types)
+def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types, cache_dir):
+ astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, cache_dir=cache_dir)
cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}")
start_time = time.monotonic()
try:
astro_dog.get_orbit_data(t, only_predictions=True)
cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s")
+ cloudlog.debug(f"Downloaded orbits ({sum([len(v) for v in astro_dog.orbits])}): {list(astro_dog.orbits.keys())}" +
+ f"With time range: {[f'{start.as_datetime()}, {end.as_datetime()}' for (start,end) in astro_dog.orbit_fetched_times._ranges]}")
return astro_dog.orbits, astro_dog.orbit_fetched_times, t
- except (RuntimeError, ValueError, IOError) as e:
+ except (DownloadFailed, RuntimeError, ValueError, IOError) as e:
cloudlog.warning(f"No orbit data found or parsing failure: {e}")
return None, None, t
@@ -301,6 +311,7 @@ def main(sm=None, pm=None):
replay = "REPLAY" in os.environ
use_internet = "LAIKAD_NO_INTERNET" not in os.environ
laikad = Laikad(save_ephemeris=not replay, auto_fetch_orbits=use_internet)
+
while True:
sm.update()
diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py
index c10a470d1a..bc7a0d7fa4 100755
--- a/selfdrive/locationd/test/test_laikad.py
+++ b/selfdrive/locationd/test/test_laikad.py
@@ -8,6 +8,7 @@ from unittest.mock import Mock, patch
from common.params import Params
from laika.constants import SECS_IN_DAY
+from laika.downloader import DownloadFailed
from laika.ephemeris import EphemerisType, GPSEphemeris
from laika.gps_time import GPSTime
from laika.helpers import ConstellationId, TimeRangeHolder
@@ -51,6 +52,9 @@ def get_measurement_mock(gpstime, sat_ephemeris):
return meas
+GPS_TIME_PREDICTION_ORBITS_RUSSIAN_SRC = GPSTime.from_datetime(datetime(2022, month=1, day=29, hour=12))
+
+
class TestLaikad(unittest.TestCase):
@classmethod
@@ -109,7 +113,7 @@ class TestLaikad(unittest.TestCase):
data_mock = defaultdict(str)
data_mock['sv_id'] = 1
- gpstime = GPSTime.from_datetime(datetime(2022, month=3, day=1))
+ gpstime = GPS_TIME_PREDICTION_ORBITS_RUSSIAN_SRC
laikad = Laikad()
laikad.fetch_orbits(gpstime, block=True)
meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['R01'][0])
@@ -165,7 +169,13 @@ class TestLaikad(unittest.TestCase):
@mock.patch('laika.downloader.download_and_cache_file')
def test_laika_offline(self, downloader_mock):
- downloader_mock.side_effect = IOError
+ downloader_mock.side_effect = DownloadFailed("Mock download failed")
+ laikad = Laikad(auto_update=False)
+ laikad.fetch_orbits(GPS_TIME_PREDICTION_ORBITS_RUSSIAN_SRC, block=True)
+
+ @mock.patch('laika.downloader.download_and_cache_file')
+ def test_download_failed_russian_source(self, downloader_mock):
+ downloader_mock.side_effect = DownloadFailed
laikad = Laikad(auto_update=False)
correct_msgs = verify_messages(self.logs, laikad)
self.assertEqual(16, len(correct_msgs))
diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py
index 057e46cd9c..bf6daf5fed 100755
--- a/selfdrive/test/process_replay/compare_logs.py
+++ b/selfdrive/test/process_replay/compare_logs.py
@@ -46,11 +46,25 @@ def remove_ignored_fields(msg, ignore):
return msg.as_reader()
-def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None):
+def get_field_tolerance(diff_field, field_tolerances):
+ diff_field_str = diff_field[0]
+ for s in diff_field[1:]:
+ # loop until number in field
+ if not isinstance(s, str):
+ break
+ diff_field_str += '.'+s
+ if diff_field_str in field_tolerances:
+ return field_tolerances[diff_field_str]
+
+
+def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None, field_tolerances=None):
if ignore_fields is None:
ignore_fields = []
if ignore_msgs is None:
ignore_msgs = []
+ if field_tolerances is None:
+ field_tolerances = {}
+ default_tolerance = EPSILON if tolerance is None else tolerance
log1, log2 = (list(filter(lambda m: m.which() not in ignore_msgs, log)) for log in (log1, log2))
@@ -72,7 +86,6 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=Non
msg1_dict = msg1.to_dict(verbose=True)
msg2_dict = msg2.to_dict(verbose=True)
- tolerance = EPSILON if tolerance is None else tolerance
dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields)
# Dictdiffer only supports relative tolerance, we also want to check for absolute
@@ -80,10 +93,13 @@ def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=Non
def outside_tolerance(diff):
try:
if diff[0] == "change":
+ field_tolerance = default_tolerance
+ if (tol := get_field_tolerance(diff[1], field_tolerances)) is not None:
+ field_tolerance = tol
a, b = diff[2]
finite = math.isfinite(a) and math.isfinite(b)
if finite and isinstance(a, numbers.Number) and isinstance(b, numbers.Number):
- return abs(a - b) > max(tolerance, tolerance * max(abs(a), abs(b)))
+ return abs(a - b) > max(field_tolerance, field_tolerance * max(abs(a), abs(b)))
except TypeError:
pass
return True
diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py
index c667aa3887..0c642cde17 100755
--- a/selfdrive/test/process_replay/process_replay.py
+++ b/selfdrive/test/process_replay/process_replay.py
@@ -14,6 +14,7 @@ from cereal import car, log
from cereal.services import service_list
from common.params import Params
from common.timeout import Timeout
+from common.realtime import DT_CTRL
from panda.python import ALTERNATIVE_EXPERIENCE
from selfdrive.car.car_helpers import get_car, interfaces
from selfdrive.test.process_replay.helpers import OpenpilotPrefix
@@ -27,7 +28,7 @@ TIMEOUT = 15
PROC_REPLAY_DIR = os.path.dirname(os.path.abspath(__file__))
FAKEDATA = os.path.join(PROC_REPLAY_DIR, "fakedata/")
-ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config', 'environ', 'subtest_name'], defaults=({}, {}, ""))
+ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config', 'environ', 'subtest_name', "field_tolerances"], defaults=({}, {}, "", {}))
def wait_for_event(evt):
@@ -548,11 +549,17 @@ def cpp_replay_process(cfg, lr, fingerprint=None):
def check_enabled(msgs):
+ cur_enabled_count = 0
+ max_enabled_count = 0
for msg in msgs:
if msg.which() == "carParams":
if msg.carParams.notCar:
return True
elif msg.which() == "controlsState":
if msg.controlsState.active:
- return True
- return False
+ cur_enabled_count += 1
+ else:
+ cur_enabled_count = 0
+ max_enabled_count = max(max_enabled_count, cur_enabled_count)
+
+ return max_enabled_count > int(10. / DT_CTRL)
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 65ecbb4be3..00bf28ed83 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-825acfae98543c915c18d3b19a9c5d2503e431a6
\ No newline at end of file
+7c1168af0311d2fef67b82812cd863a0e97c030e
\ No newline at end of file
diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py
index 1a2d436f1a..39f75ce428 100755
--- a/selfdrive/test/process_replay/regen.py
+++ b/selfdrive/test/process_replay/regen.py
@@ -263,7 +263,7 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False):
seg_path = os.path.join(outdir, segment)
# check to make sure openpilot is engaged in the route
if not check_enabled(LogReader(os.path.join(seg_path, "rlog"))):
- raise Exception(f"Route never enabled: {segment}")
+ raise Exception(f"Route did not engage for long enough: {segment}")
return seg_path
diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py
index 652c49db3d..08933d143f 100755
--- a/selfdrive/test/process_replay/test_processes.py
+++ b/selfdrive/test/process_replay/test_processes.py
@@ -18,14 +18,14 @@ from tools.lib.logreader import LogReader
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--1"), # HYUNDAI.KIA_EV6
+ ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), # 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
("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC)
("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH)
("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA
- ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--2"), # CHRYSLER.RAM_1500
+ ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), # CHRYSLER.RAM_1500
("SUBARU", "4d70bc5e608678be|2021-01-15--17-02-04--5"), # SUBARU.IMPREZA
("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT
("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL
@@ -38,17 +38,18 @@ original_segments = [
segments = [
("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"),
- ("HYUNDAI", "regen657E25856BB|2022-07-06--14-26-51--0"),
+ ("HYUNDAI", "regen114E5FF24D8|2022-07-14--17-08-47--0"),
+ ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"),
("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"),
- ("HONDA", "regen17B09D158B8|2022-07-06--14-31-46--0"),
- ("HONDA2", "regen041739C3E9A|2022-07-06--15-08-02--0"),
- ("CHRYSLER", "regenBB2F9C1425C|2022-07-06--14-31-41--0"),
- ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--2"),
- ("SUBARU", "regen732B69F33B1|2022-07-06--14-36-18--0"),
+ ("HONDA", "regenE62960EEC38|2022-07-14--19-33-24--0"),
+ ("HONDA2", "regenC3EBD92F029|2022-07-14--19-29-47--0"),
+ ("CHRYSLER", "regen38346FB33D0|2022-07-14--18-05-26--0"),
+ ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"),
+ ("SUBARU", "regen54A1E2BE5AA|2022-07-14--18-07-50--0"),
("GM", "regen01D09D915B5|2022-07-06--14-36-20--0"),
- ("NISSAN", "regenEA6FB2773F5|2022-07-06--14-58-23--0"),
+ ("NISSAN", "regenCA0B0DC946E|2022-07-14--18-10-17--0"),
("VOLKSWAGEN", "regen007098CA0EF|2022-07-06--15-01-26--0"),
("MAZDA", "regen61BA413D53B|2022-07-06--14-39-42--0"),
]
@@ -65,7 +66,7 @@ def run_test_process(data):
res = None
if not args.upload_only:
lr = LogReader.from_bytes(lr_dat)
- res, log_msgs = test_process(cfg, lr, ref_log_path, args.ignore_fields, args.ignore_msgs)
+ res, log_msgs = test_process(cfg, lr, ref_log_path, cur_log_fn, args.ignore_fields, args.ignore_msgs)
# save logs so we can upload when updating refs
save_log(cur_log_fn, log_msgs)
@@ -83,7 +84,7 @@ def get_log_data(segment):
return (segment, f.read())
-def test_process(cfg, lr, ref_log_path, ignore_fields=None, ignore_msgs=None):
+def test_process(cfg, lr, ref_log_path, new_log_path, ignore_fields=None, ignore_msgs=None):
if ignore_fields is None:
ignore_fields = []
if ignore_msgs is None:
@@ -96,10 +97,10 @@ def test_process(cfg, lr, ref_log_path, ignore_fields=None, ignore_msgs=None):
# check to make sure openpilot is engaged in the route
if cfg.proc_name == "controlsd":
if not check_enabled(log_msgs):
- raise Exception(f"Route never enabled: {ref_log_path}")
+ return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs
try:
- return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance), log_msgs
+ return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance, cfg.field_tolerances), log_msgs
except Exception as e:
return str(e), log_msgs
@@ -216,7 +217,7 @@ if __name__ == "__main__":
results: Any = defaultdict(dict)
p2 = pool.map(run_test_process, pool_args)
for (segment, proc, subtest_name, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)):
- if isinstance(result, list):
+ if not args.upload_only:
results[segment][proc + subtest_name] = result
diff1, diff2, failed = format_diff(results, ref_commit)
diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc
index a486110a73..3967416f73 100644
--- a/selfdrive/ui/qt/maps/map.cc
+++ b/selfdrive/ui/qt/maps/map.cc
@@ -526,6 +526,10 @@ void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruct
fn += "turn_straight";
}
+ if (!active) {
+ fn += "_inactive";
+ }
+
auto icon = new QLabel;
int wh = active ? 125 : 75;
icon->setPixmap(loadPixmap(fn + ICON_SUFFIX, {wh, wh}, Qt::IgnoreAspectRatio));
diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc
index eaa8b1f703..d143b44e70 100644
--- a/selfdrive/ui/qt/maps/map_settings.cc
+++ b/selfdrive/ui/qt/maps/map_settings.cc
@@ -104,7 +104,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) {
screenshot->setPixmap(pm.scaledToWidth(1080, Qt::SmoothTransformation));
no_prime_layout->addWidget(screenshot, 0, Qt::AlignHCenter);
- QLabel *signup = new QLabel(tr("Get turn-by-turn directions displayed and more with a comma \nprime subscription. Sign up now: https://connect.comma.ai"));
+ QLabel *signup = new QLabel(tr("Get turn-by-turn directions displayed and more with a comma\nprime subscription. Sign up now: https://connect.comma.ai"));
signup->setStyleSheet(R"(font-size: 45px; color: white; font-weight:300;)");
signup->setAlignment(Qt::AlignCenter);
diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc
index 536ca495ca..c7341d1987 100644
--- a/selfdrive/ui/qt/offroad/networking.cc
+++ b/selfdrive/ui/qt/offroad/networking.cc
@@ -84,7 +84,7 @@ void Networking::connectToNetwork(const Network &n) {
} else if (n.security_type == SecurityType::OPEN) {
wifi->connect(n);
} else if (n.security_type == SecurityType::WPA) {
- QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"") + n.ssid + "\"", true, 8);
+ QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"%1\"").arg(QString::fromUtf8(n.ssid)), true, 8);
if (!pass.isEmpty()) {
wifi->connect(n, pass);
}
@@ -94,7 +94,7 @@ void Networking::connectToNetwork(const Network &n) {
void Networking::wrongPassword(const QString &ssid) {
if (wifi->seenNetworks.contains(ssid)) {
const Network &n = wifi->seenNetworks.value(ssid);
- QString pass = InputDialog::getText(tr("Wrong password"), this, tr("for \"") + n.ssid +"\"", true, 8);
+ QString pass = InputDialog::getText(tr("Wrong password"), this, tr("for \"%1\"").arg(QString::fromUtf8(n.ssid)), true, 8);
if (!pass.isEmpty()) {
wifi->connect(n, pass);
}
@@ -174,7 +174,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid
list->addItem(editApnButton);
// Set initial config
- wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn")));
+ wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn")));
main_layout->addWidget(new ScrollView(list, this));
main_layout->addStretch(1);
@@ -296,7 +296,7 @@ void WifiUI::refresh() {
QPushButton *forgetBtn = new QPushButton(tr("FORGET"));
forgetBtn->setObjectName("forgetBtn");
QObject::connect(forgetBtn, &QPushButton::clicked, [=]() {
- if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"") + QString::fromUtf8(network.ssid) + "\"?", this)) {
+ if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"%1\"?").arg(QString::fromUtf8(network.ssid)), this)) {
wifi->forgetConnection(network.ssid);
}
});
diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc
index d5b8d4bbd1..9a6e203966 100644
--- a/selfdrive/ui/qt/offroad/settings.cc
+++ b/selfdrive/ui/qt/offroad/settings.cc
@@ -102,7 +102,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
// offroad-only buttons
auto dcamBtn = new ButtonControl(tr("Driver Camera"), tr("PREVIEW"),
- tr("Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)"));
+ tr("Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)"));
connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); });
addItem(dcamBtn);
@@ -249,7 +249,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) {
});
- auto uninstallBtn = new ButtonControl(tr("Uninstall ") + getBrand(), tr("UNINSTALL"));
+ auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL"));
connect(uninstallBtn, &ButtonControl::clicked, [&]() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), this)) {
params.putBool("DoUninstall", true);
diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc
index b0facfce83..dc54a3621c 100644
--- a/selfdrive/ui/qt/widgets/input.cc
+++ b/selfdrive/ui/qt/widgets/input.cc
@@ -165,7 +165,7 @@ void InputDialog::handleEnter() {
done(QDialog::Accepted);
emitText(line->text());
} else {
- setMessage(tr("Need at least ") + QString::number(minLength) + tr(" characters!"), false);
+ setMessage(tr("Need at least %1 characters!").arg(minLength), false);
}
}
diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc
index d2529821f4..5419475262 100644
--- a/selfdrive/ui/qt/widgets/prime.cc
+++ b/selfdrive/ui/qt/widgets/prime.cc
@@ -88,13 +88,16 @@ PairingPopup::PairingPopup(QWidget *parent) : QDialogBase(parent) {
title->setWordWrap(true);
vlayout->addWidget(title);
- QLabel *instructions = new QLabel(tr(R"(
+ QLabel *instructions = new QLabel(QString(R"(