diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index a504e2b135..04ae841f77 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -7,6 +7,7 @@ on: env: BASE_IMAGE: openpilot-base + CL_BASE_IMAGE: openpilot-base-cl DOCKER_REGISTRY: ghcr.io/commaai AZURE_TOKEN: ${{ secrets.AZURE_COMMADATACI_OPENPILOTCI_TOKEN }} @@ -17,6 +18,13 @@ env: 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 + + BUILD_CL: | + docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base_cl) || true + docker pull $DOCKER_REGISTRY/$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 + UNIT_TEST: coverage run --append -m unittest discover jobs: @@ -193,10 +201,13 @@ jobs: submodules: true - name: Build Docker image run: eval "$BUILD" + - name: Build CL Docker image + run: eval "$BUILD_CL" - name: Push to container registry run: | $DOCKER_LOGIN docker push $DOCKER_REGISTRY/$BASE_IMAGE:latest + docker push $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest static_analysis: name: static analysis @@ -295,7 +306,7 @@ jobs: ./common/tests/test_swaglog && \ ./selfdrive/boardd/tests/test_boardd_usbprotocol && \ ./selfdrive/loggerd/tests/test_logger &&\ - ./selfdrive/proclogd/tests/test_proclog && \ + ./system/proclogd/tests/test_proclog && \ ./selfdrive/ui/replay/tests/test_replay && \ ./selfdrive/camerad/test/ae_gray_test && \ coverage xml" @@ -351,6 +362,44 @@ jobs: CI=1 AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only" - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v2 + + model_replay_onnx: + name: model replay onnx + runs-on: ubuntu-20.04 + timeout-minutes: 50 + steps: + - uses: actions/checkout@v3 + with: + submodules: true + - name: Pull LFS + run: git lfs pull + - name: Cache dependencies + id: dependency-cache + uses: actions/cache@v2 + with: + path: /tmp/comma_download_cache + key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/model_replay.py') }} + - name: Cache scons + id: scons-cache + # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. + uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b + env: + CACHE_SKIP_SAVE: true + with: + path: /tmp/scons_cache + key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- + restore-keys: | + scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- + scons- + - name: Build Docker image + # Sim docker is needed to get the intel OPENCL drivers + run: eval "$BUILD_CL" + - name: Run replay + run: | + ${{ env.RUN_CL }} "scons -j$(nproc) && \ + ONNXCPU=1 FILEREADER_CACHE=1 CI=1 coverage run \ + selfdrive/test/process_replay/model_replay.py -j$(nproc) && \ + coverage xml" test_longitudinal: name: longitudinal diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 7b01728e5c..1e4ce7a4ae 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -5,6 +5,7 @@ on: env: BASE_IMAGE: openpilot-base + CL_BASE_IMAGE: openpilot-base-cl DOCKER_REGISTRY: ghcr.io/commaai DOCKER_LOGIN: docker login ghcr.io -u adeebshihadeh -p ${{ secrets.CONTAINER_TOKEN }} @@ -12,6 +13,10 @@ env: docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . + BUILD_CL: | + docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base_cl) || true + docker pull $DOCKER_REGISTRY/$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: docker run --shm-size 1G -v $PWD:/tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e \ GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c @@ -49,8 +54,10 @@ jobs: run: git lfs pull - name: Build base image run: eval "$BUILD" + - name: Build base cl image + run: eval "$BUILD_CL" - name: Pull latest simulator image - run: eval "$BUILD"docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true + run: docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true - name: Build simulator image run: docker build --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f tools/sim/Dockerfile.sim . - name: Push to container registry diff --git a/.gitignore b/.gitignore index 83ccbb4781..334b1b4fed 100644 --- a/.gitignore +++ b/.gitignore @@ -41,7 +41,7 @@ board/obj/ selfdrive/boardd/boardd selfdrive/logcatd/logcatd selfdrive/mapd/default_speeds_by_region.json -selfdrive/proclogd/proclogd +system/proclogd/proclogd selfdrive/ui/_ui selfdrive/test/longitudinal_maneuvers/out selfdrive/visiond/visiond diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot index daf85f8183..66b9f18a11 100644 --- a/Dockerfile.openpilot +++ b/Dockerfile.openpilot @@ -28,5 +28,6 @@ COPY ./opendbc ${OPENPILOT_PATH}/opendbc COPY ./cereal ${OPENPILOT_PATH}/cereal COPY ./panda ${OPENPILOT_PATH}/panda COPY ./selfdrive ${OPENPILOT_PATH}/selfdrive +COPY ./system ${OPENPILOT_PATH}/system RUN scons -j$(nproc) diff --git a/Dockerfile.openpilot_base_cl b/Dockerfile.openpilot_base_cl new file mode 100644 index 0000000000..7652b7e4e6 --- /dev/null +++ b/Dockerfile.openpilot_base_cl @@ -0,0 +1,37 @@ +FROM ghcr.io/commaai/openpilot-base:latest + +RUN apt-get update && apt-get install -y --no-install-recommends\ + apt-utils \ + alien \ + unzip \ + tar \ + curl \ + xz-utils \ + dbus \ + gcc-arm-none-eabi \ + tmux \ + vim \ + lsb-core \ + libx11-6 \ + && rm -rf /var/lib/apt/lists/* + +# Intel OpenCL driver +ARG INTEL_DRIVER=l_opencl_p_18.1.0.015.tgz +ARG INTEL_DRIVER_URL=http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532 +RUN mkdir -p /tmp/opencl-driver-intel +WORKDIR /tmp/opencl-driver-intel +RUN echo INTEL_DRIVER is $INTEL_DRIVER && \ + curl -O $INTEL_DRIVER_URL/$INTEL_DRIVER && \ + tar -xzf $INTEL_DRIVER && \ + for i in $(basename $INTEL_DRIVER .tgz)/rpm/*.rpm; do alien --to-deb $i; done && \ + dpkg -i *.deb && \ + rm -rf $INTEL_DRIVER $(basename $INTEL_DRIVER .tgz) *.deb && \ + mkdir -p /etc/OpenCL/vendors && \ + echo /opt/intel/opencl_compilers_and_libraries_18.1.0.015/linux/compiler/lib/intel64_lin/libintelocl.so > /etc/OpenCL/vendors/intel.icd && \ + rm -rf /tmp/opencl-driver-intel +ENV NVIDIA_VISIBLE_DEVICES all +ENV NVIDIA_DRIVER_CAPABILITIES graphics,utility,compute +ENV QTWEBENGINE_DISABLE_SANDBOX 1 + +RUN dbus-uuidgen > /etc/machine-id + diff --git a/README.md b/README.md index 5af02de8d9..9d279fb84d 100755 --- a/README.md +++ b/README.md @@ -102,6 +102,9 @@ Directory Structure ├── panda # Code used to communicate on CAN ├── third_party # External libraries ├── pyextra # Extra python packages + └── system # Generic services + ├── 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 @@ -112,7 +115,6 @@ Directory Structure ├── controls # Planning and controls ├── debug # Tools to help you debug and do car ports ├── locationd # Precise localization and vehicle parameter estimation - ├── logcatd # Android logcat as a service ├── loggerd # Logger and uploader of car data ├── modeld # Driving and monitoring model runners ├── proclogd # Logs information from proc diff --git a/RELEASES.md b/RELEASES.md index c02a54413c..de57d520d3 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -5,6 +5,7 @@ Version 0.8.15 (2022-XX-XX) * Much smoother control, consistent across the speed range * Effective feedforward that uses road roll * Simplified tuning, all car-specific parameters can be derived from data +* AGNOS 5 Version 0.8.14 (2022-06-01) ======================== diff --git a/SConstruct b/SConstruct index e6141f7385..0aeb382c23 100644 --- a/SConstruct +++ b/SConstruct @@ -377,6 +377,14 @@ if arch != "larch64": Export('rednose_config') SConscript(['rednose/SConscript']) +# Build system services +SConscript([ + 'system/clocksd/SConscript', + 'system/proclogd/SConscript', +]) +if arch != "Darwin": + SConscript(['system/logcatd/SConscript']) + # Build openpilot SConscript(['cereal/SConscript']) @@ -396,8 +404,6 @@ SConscript(['selfdrive/controls/lib/lateral_mpc_lib/SConscript']) SConscript(['selfdrive/controls/lib/longitudinal_mpc_lib/SConscript']) SConscript(['selfdrive/boardd/SConscript']) -SConscript(['selfdrive/proclogd/SConscript']) -SConscript(['selfdrive/clocksd/SConscript']) SConscript(['selfdrive/loggerd/SConscript']) @@ -405,9 +411,6 @@ SConscript(['selfdrive/locationd/SConscript']) SConscript(['selfdrive/sensord/SConscript']) SConscript(['selfdrive/ui/SConscript']) -if arch != "Darwin": - SConscript(['selfdrive/logcatd/SConscript']) - if GetOption('test'): SConscript('panda/tests/safety/SConscript') diff --git a/common/params.cc b/common/params.cc index 2338969600..330eddc1a9 100644 --- a/common/params.cc +++ b/common/params.cc @@ -104,7 +104,6 @@ std::unordered_map keys = { {"DoReboot", CLEAR_ON_MANAGER_START}, {"DoShutdown", CLEAR_ON_MANAGER_START}, {"DoUninstall", CLEAR_ON_MANAGER_START}, - {"EndToEndToggle", PERSISTENT}, {"ForcePowerDown", CLEAR_ON_MANAGER_START}, {"GitBranch", PERSISTENT}, {"GitCommit", PERSISTENT}, diff --git a/docs/CARS.md b/docs/CARS.md index 87be32f1d0..2aa624d849 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -51,13 +51,7 @@ How We Rate The Cars |Lexus|ES 2019-21|All|||||| |Lexus|ES Hybrid 2019-22|All|||||| |Lexus|NX 2020|All|||||| -|Lexus|RX 2020-22|All|||||| -|Lexus|RX Hybrid 2020-21|All|||||| |Lexus|UX Hybrid 2019-21|All|||||| -|Toyota|Alphard 2019-20|All|||||| -|Toyota|Alphard Hybrid 2021|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|||||| @@ -75,12 +69,7 @@ How We Rate The Cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| -|Audi|A3 2014-19|ACC + Lane Assist|||||| -|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|||||| |Audi|Q2 2018|ACC + Lane Assist|||||| -|Audi|Q3 2020-21|ACC + Lane Assist|||||| -|Audi|RS3 2018|ACC + Lane Assist|||||| -|Audi|S3 2015-17|ACC + Lane Assist|||||| |Genesis|G70 2018|All|||||| |Genesis|G80 2018|All|||||| |Hyundai|Elantra 2021-22|SCC + LKAS|||||| @@ -94,7 +83,6 @@ How We Rate The Cars |Hyundai|Santa Fe 2021-22|All|||||| |Hyundai|Santa Fe Hybrid 2022|All|||||| |Hyundai|Santa Fe Plug-in Hybrid 2022|All|||||| -|Hyundai|Sonata 2018-19|SCC + LKAS|||||| |Hyundai|Tucson Diesel 2019|SCC + LKAS|||||| |Kia|Ceed 2019|SCC + LKAS|||||| |Kia|Forte 2018|SCC + LKAS|||||| @@ -107,18 +95,15 @@ How We Rate The Cars |Kia|Sorento 2018|SCC + LKAS|||||| |Kia|Sorento 2019|SCC + LKAS|||||| |Kia|Stinger 2018|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)||||| |Lexus|NX Hybrid 2018-19|All|[3](#footnotes)||||| -|Lexus|RX 2016-18|All|[3](#footnotes)||||| -|Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| +|Lexus|RX 2020-22|All|||||| +|Lexus|RX Hybrid 2020-21|All|||||| |Mazda|CX-5 2022|All|||||| |SEAT|Ateca 2018|Driver Assistance|||||| |SEAT|Leon 2014-20|Driver Assistance|||||| -|Subaru|Crosstrek 2018-19|EyeSight|||||| |Subaru|Forester 2019-21|EyeSight|||||| -|Subaru|Impreza 2017-19|EyeSight|||||| |Škoda|Kamiq 2021[6](#footnotes)|Driver Assistance|||||| |Škoda|Karoq 2019|Driver Assistance|||||| |Škoda|Kodiaq 2018-19|Driver Assistance|||||| @@ -126,36 +111,20 @@ How We Rate The Cars |Škoda|Octavia RS 2016|Driver Assistance|||||| |Škoda|Scala 2020|Driver Assistance|||||| |Škoda|Superb 2015-18|Driver Assistance|||||| -|Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|C-HR 2017-21|All|||||| -|Toyota|C-HR Hybrid 2017-19|All|||||| +|Toyota|Alphard 2019-20|All|||||| +|Toyota|Alphard Hybrid 2021|All|||||| +|Toyota|Avalon 2022|All|||||| +|Toyota|Avalon Hybrid 2022|All|||||| |Toyota|Camry 2018-20|All||[4](#footnotes)|||| |Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| -|Toyota|Highlander 2017-19|All|[3](#footnotes)||||| -|Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| |Toyota|RAV4 2022|All|||||| -|Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| |Toyota|RAV4 Hybrid 2022|All|||||| -|Toyota|Sienna 2018-20|All|[3](#footnotes)||||| |Volkswagen|Arteon 2018, 2021[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Atlas 2018-19, 2022[8](#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|Jetta 2018-21|Driver Assistance|||||| -|Volkswagen|Jetta GLI 2021|Driver Assistance|||||| -|Volkswagen|Passat 2015-18[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|Passat 2015-19[7](#footnotes)|Driver Assistance|||||| |Volkswagen|Polo 2020|Driver Assistance|||||| |Volkswagen|T-Cross 2021[8](#footnotes)|Driver Assistance|||||| |Volkswagen|T-Roc 2021[8](#footnotes)|Driver Assistance|||||| |Volkswagen|Taos 2022[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Tiguan 2019-22[8](#footnotes)|Driver Assistance|||||| |Volkswagen|Touran 2017|Driver Assistance|||||| ## Bronze Cars @@ -165,6 +134,11 @@ How We Rate The Cars |Acura|ILX 2016-19|AcuraWatch Plus|||||| |Acura|RDX 2016-18|AcuraWatch Plus|||||| |Acura|RDX 2019-21|All|||||| +|Audi|A3 2014-19|ACC + Lane Assist|||||| +|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|||||| +|Audi|Q3 2020-21|ACC + Lane Assist|||||| +|Audi|RS3 2018|ACC + Lane Assist|||||| +|Audi|S3 2015-17|ACC + Lane Assist|||||| |Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| |Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| @@ -196,29 +170,55 @@ How We Rate The Cars |Hyundai|Ioniq Electric 2019|SCC + LKAS|||||| |Hyundai|Ioniq Hybrid 2017-19|SCC + LKAS|||||| |Hyundai|Ioniq Plug-in Hybrid 2019|SCC + LKAS|||||| +|Hyundai|Sonata 2018-19|SCC + LKAS|||||| |Hyundai|Veloster 2019-20|SCC + LKAS|||||| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise|||||| |Jeep|Grand Cherokee 2019-20|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|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| +|Lexus|IS 2017-19|All|||||| +|Lexus|RC 2020|All|||||| +|Lexus|RX 2016-18|All|[3](#footnotes)||||| +|Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| |Mazda|CX-9 2021|All|||||| |Nissan|Altima 2019-20|ProPILOT|||||| |Nissan|Leaf 2018-22|ProPILOT|||||| |Nissan|Rogue 2018-20|ProPILOT|||||| |Nissan|X-Trail 2017|ProPILOT|||||| |Subaru|Ascent 2019-20|EyeSight|||||| +|Subaru|Crosstrek 2018-19|EyeSight|||||| |Subaru|Crosstrek 2020-21|EyeSight|||||| +|Subaru|Impreza 2017-19|EyeSight|||||| |Subaru|Impreza 2020-21|EyeSight|||||| -|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|C-HR 2017-21|All|||||| +|Toyota|C-HR Hybrid 2017-19|All|||||| |Toyota|Corolla 2017-19|All|[3](#footnotes)||||| +|Toyota|Highlander 2017-19|All|[3](#footnotes)||||| +|Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| |Toyota|Prius 2016-20|TSS-P|[3](#footnotes)|||[5](#footnotes)|| |Toyota|Prius Prime 2017-20|All|[3](#footnotes)|||[5](#footnotes)|| |Toyota|Prius v 2017|TSS-P|[3](#footnotes)|||[5](#footnotes)|| -|Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Sienna 2018-20|All|[3](#footnotes)||||| +|Volkswagen|Atlas 2018-19, 2022[8](#footnotes)|Driver Assistance|||||| |Volkswagen|California 2021[8](#footnotes)|Driver Assistance|||||| |Volkswagen|Caravelle 2020[8](#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|Jetta 2018-21|Driver Assistance|||||| +|Volkswagen|Jetta GLI 2021|Driver Assistance|||||| +|Volkswagen|Tiguan 2019-22[8](#footnotes)|Driver Assistance|||||| diff --git a/docs/c_docs.rst b/docs/c_docs.rst index 1e080a826d..218cd5a7d9 100644 --- a/docs/c_docs.rst +++ b/docs/c_docs.rst @@ -66,7 +66,7 @@ qt proclogd ^^^^^^^^ .. autodoxygenindex:: - :project: selfdrive_proclogd + :project: system_proclogd modeld ^^^^^^ diff --git a/docs/docker/Dockerfile b/docs/docker/Dockerfile index 124feb1bfc..cefe9be855 100644 --- a/docs/docker/Dockerfile +++ b/docs/docker/Dockerfile @@ -30,6 +30,7 @@ COPY ./opendbc ${OPENPILOT_PATH}/opendbc COPY ./cereal ${OPENPILOT_PATH}/cereal COPY ./panda ${OPENPILOT_PATH}/panda COPY ./selfdrive ${OPENPILOT_PATH}/selfdrive +COPY ./system ${OPENPILOT_PATH}/system COPY ./*.md ${OPENPILOT_PATH}/ RUN scons -j$(nproc) diff --git a/laika_repo b/laika_repo index 231eafbf65..d871946134 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 231eafbf659309b85acb5b575b7f898e7a4f196e +Subproject commit d87194613455b42af19ff2b5a3f7d1cae5852885 diff --git a/launch_env.sh b/launch_env.sh index d4b57c909a..769613bc79 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="4" + export AGNOS_VERSION="5.1" fi if [ -z "$PASSIVE" ]; then diff --git a/panda b/panda index 6d19b46ef5..475a9a3124 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6d19b46ef525b0ae224e0bf7db71918e96f9be66 +Subproject commit 475a9a312410908abcaa32f2e48140fcbfc2362f diff --git a/release/files_common b/release/files_common index 974ea27711..ceb0110606 100644 --- a/release/files_common +++ b/release/files_common @@ -119,9 +119,9 @@ selfdrive/car/tesla/*.py selfdrive/car/toyota/*.py selfdrive/car/volkswagen/*.py -selfdrive/clocksd/.gitignore -selfdrive/clocksd/SConscript -selfdrive/clocksd/clocksd.cc +system/clocksd/.gitignore +system/clocksd/SConscript +system/clocksd/clocksd.cc selfdrive/debug/*.py @@ -220,13 +220,13 @@ selfdrive/locationd/models/live_kf.cc selfdrive/locationd/calibrationd.py -selfdrive/logcatd/SConscript -selfdrive/logcatd/logcatd_systemd.cc +system/logcatd/SConscript +system/logcatd/logcatd_systemd.cc -selfdrive/proclogd/SConscript -selfdrive/proclogd/main.cc -selfdrive/proclogd/proclog.cc -selfdrive/proclogd/proclog.h +system/proclogd/SConscript +system/proclogd/main.cc +system/proclogd/proclog.cc +system/proclogd/proclog.h selfdrive/loggerd/SConscript selfdrive/loggerd/encoder/encoder.cc diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 806a060f97..c77e40daaf 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -24,12 +24,13 @@ def create_button_event(cur_but: int, prev_but: int, buttons_dict: Dict[int, cap return be -def create_button_enable_events(buttonEvents: capnp.lib.capnp._DynamicListBuilder) -> List[int]: +def create_button_enable_events(buttonEvents: capnp.lib.capnp._DynamicListBuilder, pcm_cruise: bool = False) -> List[int]: events = [] for b in buttonEvents: # do enable on both accel and decel buttons - if b.type in (ButtonType.accelCruise, ButtonType.decelCruise) and not b.pressed: - events.append(EventName.buttonEnable) + if not pcm_cruise: + if b.type in (ButtonType.accelCruise, ButtonType.decelCruise) and not b.pressed: + events.append(EventName.buttonEnable) # do disable on button down if b.type == ButtonType.cancel and b.pressed: events.append(EventName.buttonCancel) diff --git a/selfdrive/car/body/interface.py b/selfdrive/car/body/interface.py index 2b44200397..3d6bd5e22a 100644 --- a/selfdrive/car/body/interface.py +++ b/selfdrive/car/body/interface.py @@ -17,6 +17,7 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.body)] ret.minSteerSpeed = -math.inf + ret.maxLateralAccel = math.inf # TODO: set to a reasonable value ret.steerRatio = 0.5 ret.steerRateCost = 0.5 ret.steerLimitTimer = 1.0 diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py index a009b40bc9..0caf93b619 100644 --- a/selfdrive/car/body/values.py +++ b/selfdrive/car/body/values.py @@ -18,7 +18,7 @@ class CAR: BODY = "COMMA BODY" CAR_INFO: Dict[str, CarInfo] = { - CAR.BODY: CarInfo("comma body", package="All", good_torque=True, harness=Harness.none), + CAR.BODY: CarInfo("comma body", package="All", harness=Harness.none), } FW_VERSIONS = { diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 85fcfa1fad..7863f0d882 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -1,9 +1,11 @@ import os -from typing import Any, Dict, List +from typing import Dict, List +from cereal import car from common.params import Params from common.basedir import BASEDIR from selfdrive.version import is_comma_remote, is_tested_branch +from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car @@ -11,7 +13,6 @@ from selfdrive.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint -from cereal import car EventName = car.CarEvent.EventName @@ -59,19 +60,6 @@ def load_interfaces(brand_names): return ret -def get_interface_attr(attr: str) -> Dict[str, Any]: - # returns given attribute from each interface - brand_names = {} - for car_folder in sorted([x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]): - try: - brand_name = car_folder.split('/')[-1] - attr_data = getattr(__import__(f'selfdrive.car.{brand_name}.values', fromlist=[attr]), attr, None) - brand_names[brand_name] = attr_data - except (ImportError, OSError): - pass - return brand_names - - def _get_interface_names() -> Dict[str, List[str]]: # returns a dict of brand name and its respective models brand_names = {} @@ -116,6 +104,9 @@ def fingerprint(logcan, sendcan): vin = VIN_UNKNOWN exact_fw_match, fw_candidates, car_fw = True, set(), [] + if len(vin) != 17: + cloudlog.event("Malformed VIN", vin=vin, error=True) + vin = VIN_UNKNOWN cloudlog.warning("VIN %s", vin) Params().put("CarVin", vin) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 55672dd4ab..e47b085533 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -23,6 +23,14 @@ class CarInterface(CarInterfaceBase): ret.steerRateCost = 0.7 ret.steerLimitTimer = 0.4 + # set max lateral acceleration + if candidate in (CAR.PACIFICA_2018, CAR.PACIFICA_2019_HYBRID, CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): + ret.maxLateralAccel = 1.6 + if candidate in (CAR.PACIFICA_2018_HYBRID,): + ret.maxLateralAccel = 1.4 + if candidate in (CAR.PACIFICA_2017_HYBRID,): + ret.maxLateralAccel = 1.2 + if candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): ret.wheelbase = 2.91 # in meters ret.steerRatio = 12.7 diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index fad110689c..899f2c0878 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -15,9 +15,8 @@ from selfdrive.car.tests.routes import non_tested_cars def get_all_footnotes() -> Dict[Enum, int]: all_footnotes = [] - for _, footnotes in get_interface_attr("Footnote").items(): - if footnotes is not None: - all_footnotes += footnotes + for footnotes in get_interface_attr("Footnote", ignore_none=True).values(): + all_footnotes += footnotes return {fn: idx + 1 for idx, fn in enumerate(all_footnotes)} @@ -28,21 +27,20 @@ CARS_MD_TEMPLATE = os.path.join(BASEDIR, "selfdrive", "car", "CARS_template.md") def get_all_car_info() -> List[CarInfo]: all_car_info: List[CarInfo] = [] - for models in get_interface_attr("CAR_INFO").values(): - for model, car_info in models.items(): - # Hyundai exception: those with radar have openpilot longitudinal - fingerprint = {0: {}, 1: {HKG_RADAR_START_ADDR: 8}, 2: {}, 3: {}} - CP = interfaces[model][0].get_params(model, fingerprint=fingerprint, disable_radar=True) + for model, car_info in get_interface_attr("CAR_INFO", combine_brands=True).items(): + # Hyundai exception: those with radar have openpilot longitudinal + fingerprint = {0: {}, 1: {HKG_RADAR_START_ADDR: 8}, 2: {}, 3: {}} + CP = interfaces[model][0].get_params(model, fingerprint=fingerprint, disable_radar=True) - if CP.dashcamOnly or car_info is None: - continue + if CP.dashcamOnly or car_info is None: + continue - # A platform can include multiple car models - if not isinstance(car_info, list): - car_info = (car_info,) + # A platform can include multiple car models + if not isinstance(car_info, list): + car_info = (car_info,) - for _car_info in car_info: - all_car_info.append(_car_info.init(CP, non_tested_cars, ALL_FOOTNOTES)) + for _car_info in car_info: + all_car_info.append(_car_info.init(CP, non_tested_cars, ALL_FOOTNOTES)) # Sort cars by make and model + year sorted_cars: List[CarInfo] = natsorted(all_car_info, key=lambda car: (car.make + car.model).lower()) diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 3046f5c9e3..95561872ac 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -1,9 +1,13 @@ +import math + from cereal import car from collections import namedtuple from dataclasses import dataclass from enum import Enum from typing import Dict, List, Optional, Union, no_type_check +STEERING_TORQUE_THRESHOLD = 2.0 # m/s^2 + class Tier(Enum): GOLD = "The best openpilot experience. Great highway driving and beyond." @@ -66,6 +70,11 @@ class CarInfo: if self.min_enable_speed is not None: min_enable_speed = self.min_enable_speed + # TODO: remove hardcoded good torque and just use maxLateralAccel + good_torque = self.good_torque + if not math.isnan(CP.maxLateralAccel): + good_torque = CP.maxLateralAccel >= STEERING_TORQUE_THRESHOLD + self.car_name = CP.carName self.make, self.model = self.name.split(' ', 1) self.row = { @@ -76,7 +85,7 @@ class CarInfo: Column.LONGITUDINAL: CP.openpilotLongitudinalControl and not CP.radarOffCan, Column.FSR_LONGITUDINAL: min_enable_speed <= 0., Column.FSR_STEERING: min_steer_speed <= 0., - Column.STEERING_TORQUE: self.good_torque, + Column.STEERING_TORQUE: good_torque, Column.MAINTAINED: CP.carFingerprint not in non_tested_cars and self.harness is not Harness.none, } @@ -111,7 +120,7 @@ class CarInfo: class Harness(Enum): nidec = "Honda Nidec" - bosch = "Honda Bosch" + bosch = "Honda Bosch A" toyota = "Toyota" subaru = "Subaru" fca = "FCA" diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py index 9b280f3b45..1a9bb8c4e7 100644 --- a/selfdrive/car/fingerprints.py +++ b/selfdrive/car/fingerprints.py @@ -1,44 +1,12 @@ -import os -from common.basedir import BASEDIR +from selfdrive.car.interfaces import get_interface_attr -def get_attr_from_cars(attr, result=dict, combine_brands=True): - # read all the folders in selfdrive/car and return a dict where: - # - keys are all the car models - # - values are attr values from all car folders - result = result() - - for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: - try: - car_name = car_folder.split('/')[-1] - values = __import__(f'selfdrive.car.{car_name}.values', fromlist=[attr]) - if hasattr(values, attr): - attr_values = getattr(values, attr) - else: - continue - - if isinstance(attr_values, dict): - for f, v in attr_values.items(): - if combine_brands: - result[f] = v - else: - if car_name not in result: - result[car_name] = {} - result[car_name][f] = v - elif isinstance(attr_values, list): - result += attr_values - - except (ImportError, OSError): - pass - - return result - - -FW_VERSIONS = get_attr_from_cars('FW_VERSIONS') -_FINGERPRINTS = get_attr_from_cars('FINGERPRINTS') +FW_VERSIONS = get_interface_attr('FW_VERSIONS', combine_brands=True, ignore_none=True) +_FINGERPRINTS = get_interface_attr('FINGERPRINTS', combine_brands=True, ignore_none=True) _DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes + def is_valid_for_fingerprint(msg, car_fingerprint): adr = msg.address # ignore addresses that are more than 11 bits diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 120174c451..69b7c5f452 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -1,15 +1,15 @@ #!/usr/bin/env python3 import struct import traceback -from typing import Any, List from collections import defaultdict -from dataclasses import dataclass - +from dataclasses import dataclass, field +from typing import Any, List from tqdm import tqdm import panda.python.uds as uds from cereal import car -from selfdrive.car.fingerprints import FW_VERSIONS, get_attr_from_cars +from selfdrive.car.interfaces import get_interface_attr +from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery from selfdrive.car.toyota.values import CAR as TOYOTA from selfdrive.swaglog import cloudlog @@ -96,9 +96,11 @@ class Request: brand: str request: List[bytes] response: List[bytes] + whitelist_ecus: List[int] = field(default_factory=list) rx_offset: int = DEFAULT_RX_OFFSET bus: int = 1 + REQUESTS: List[Request] = [ # Subaru Request( @@ -303,7 +305,7 @@ def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progr addrs = [] parallel_addrs = [] - versions = get_attr_from_cars('FW_VERSIONS', combine_brands=False) + versions = get_interface_attr('FW_VERSIONS', ignore_none=True) if extra is not None: versions.update(extra) @@ -328,23 +330,26 @@ def get_fw_versions(logcan, sendcan, extra=None, timeout=0.1, debug=False, progr for addr_chunk in chunks(addr): for r in REQUESTS: try: - addrs = [(a, s) for (b, a, s) in addr_chunk if b in (r.brand, 'any')] + addrs = [(a, s) for (b, a, s) in addr_chunk if b in (r.brand, 'any') and + (len(r.whitelist_ecus) == 0 or ecu_types[(a, s)] in r.whitelist_ecus)] if addrs: query = IsoTpParallelQuery(sendcan, logcan, r.bus, addrs, r.request, r.response, r.rx_offset, debug=debug) t = 2 * timeout if i == 0 else timeout - fw_versions.update(query.get_data(t)) + fw_versions.update({addr: (version, r.request, r.rx_offset) for addr, version in query.get_data(t).items()}) except Exception: cloudlog.warning(f"FW query exception: {traceback.format_exc()}") # Build capnp list to put into CarParams car_fw = [] - for addr, version in fw_versions.items(): + for addr, (version, request, rx_offset) in fw_versions.items(): f = car.CarParams.CarFw.new_message() f.ecu = ecu_types[addr] f.fwVersion = version f.address = addr[0] + f.responseAddress = addr[0] + rx_offset + f.request = request if addr[1] is not None: f.subAddress = addr[1] diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index b4265fc0bd..bc43086586 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -58,7 +58,7 @@ class CarInterface(CarInterfaceBase): ret.openpilotLongitudinalControl = True tire_stiffness_factor = 0.444 # not optimized yet - # Start with a baseline lateral tuning for all GM vehicles. Override tuning as needed in each model section below. + # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. ret.minSteerSpeed = 7 * CV.MPH_TO_MS ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] @@ -66,15 +66,24 @@ class CarInterface(CarInterfaceBase): ret.steerRateCost = 1.0 ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + ret.longitudinalTuning.kpBP = [5., 35.] + ret.longitudinalTuning.kpV = [2.4, 1.5] + ret.longitudinalTuning.kiBP = [0.] + ret.longitudinalTuning.kiV = [0.36] + + ret.steerLimitTimer = 0.4 + ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz + + # supports stop and go, but initial engage must (conservatively) be above 18mph + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + if candidate == CAR.VOLT: - # supports stop and go, but initial engage must be above 18mph (which include conservatism) - ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.mass = 1607. + STD_CARGO_KG ret.wheelbase = 2.69 ret.steerRatio = 17.7 # Stock 15.7, LiveParameters tire_stiffness_factor = 0.469 # Stock Michelin Energy Saver A/S, LiveParameters - ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.45 # Volt Gen 1, TODO corner weigh + ret.maxLateralAccel = 1.6 ret.lateralTuning.pid.kpBP = [0., 40.] ret.lateralTuning.pid.kpV = [0., 0.17] @@ -84,12 +93,9 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.2 elif candidate == CAR.MALIBU: - # supports stop and go, but initial engage must be above 18mph (which include conservatism) - ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.mass = 1496. + STD_CARGO_KG ret.wheelbase = 2.83 ret.steerRatio = 15.8 - ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 # wild guess elif candidate == CAR.HOLDEN_ASTRA: @@ -97,33 +103,27 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.662 # Remaining parameters copied from Volt for now ret.centerToFront = ret.wheelbase * 0.4 - ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.steerRatio = 15.7 - ret.steerRatioRear = 0. elif candidate == CAR.ACADIA: ret.minEnableSpeed = -1. # engage speed is decided by pcm ret.mass = 4353. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.86 ret.steerRatio = 14.4 # end to end is 13.46 - ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 - ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_acadia() + ret.maxLateralAccel = 1.4 + ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_acadia() elif candidate == CAR.BUICK_REGAL: - ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.mass = 3779. * CV.LB_TO_KG + STD_CARGO_KG # (3849+3708)/2 ret.wheelbase = 2.83 # 111.4 inches in meters ret.steerRatio = 14.4 # guess for tourx - ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 # guess for tourx elif candidate == CAR.CADILLAC_ATS: - ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.mass = 1601. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 15.3 - ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.49 elif candidate == CAR.ESCALADE_ESV: @@ -146,14 +146,6 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.longitudinalTuning.kpBP = [5., 35.] - ret.longitudinalTuning.kpV = [2.4, 1.5] - ret.longitudinalTuning.kiBP = [0.] - ret.longitudinalTuning.kiV = [0.36] - - ret.steerLimitTimer = 0.4 - ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz - return ret # returns a car.CarState diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 5b97b3389f..ad98f8863f 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -100,6 +100,7 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] else: + ret.maxLateralAccel = 1.7 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] tire_stiffness_factor = 1. @@ -112,6 +113,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.38 # 10.93 is end-to-end spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 1. + ret.maxLateralAccel = 1.6 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate in (CAR.ACCORD, CAR.ACCORDH): @@ -126,6 +128,7 @@ class CarInterface(CarInterfaceBase): if eps_modified: ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] else: + ret.maxLateralAccel = 1.6 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.ACURA_ILX: @@ -162,6 +165,7 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] else: + ret.maxLateralAccel = 1.7 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] tire_stiffness_factor = 0.677 @@ -186,6 +190,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.06 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.75 + ret.maxLateralAccel = 1.7 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] elif candidate == CAR.FREED: @@ -216,8 +221,9 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.68 ret.centerToFront = ret.wheelbase * 0.38 ret.steerRatio = 15.0 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 + ret.maxLateralAccel = 0.9 + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate == CAR.ACURA_RDX_3G: @@ -226,6 +232,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.75 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 11.95 # as spec + ret.maxLateralAccel = 1.2 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] tire_stiffness_factor = 0.677 @@ -238,6 +245,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.35 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 + ret.maxLateralAccel = 1.5 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] elif candidate == CAR.ODYSSEY_CHN: @@ -258,6 +266,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.25 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 + ret.maxLateralAccel = 1.5 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.RIDGELINE: @@ -268,6 +277,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.59 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 + ret.maxLateralAccel = 1.3 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.INSIGHT: @@ -278,6 +288,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.0 # 12.58 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 + ret.maxLateralAccel = 1.4 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.HONDA_E: @@ -367,7 +378,7 @@ class CarInterface(CarInterfaceBase): events.add(EventName.manualRestart) # handle button presses - events.events.extend(create_button_enable_events(ret.buttonEvents)) + events.events.extend(create_button_enable_events(ret.buttonEvents, self.CP.pcmCruise)) ret.events = events.to_msg() diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 673b304e5a..e051079dc4 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -60,6 +60,7 @@ class CarInterface(CarInterfaceBase): # Values from optimizer ret.steerRatio = 16.55 # 13.8 is spec end-to-end tire_stiffness_factor = 0.82 + ret.maxLateralAccel = 3.2 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): @@ -68,6 +69,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable tire_stiffness_factor = 0.65 + ret.maxLateralAccel = 2.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.SONATA_LF: @@ -75,6 +77,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 4497. * CV.LB_TO_KG ret.wheelbase = 2.804 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable + ret.maxLateralAccel = 1.8 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.PALISADE: @@ -83,6 +86,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.90 ret.steerRatio = 15.6 * 1.15 tire_stiffness_factor = 0.63 + ret.maxLateralAccel = 2.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]] elif candidate in (CAR.ELANTRA, CAR.ELANTRA_GT_I30): @@ -139,6 +143,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.7 ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 + ret.maxLateralAccel = 3.0 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate not in (CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): @@ -188,6 +193,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.7 ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec tire_stiffness_factor = 0.385 + ret.maxLateralAccel = 2.9 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate == CAR.KIA_NIRO_HEV: @@ -219,6 +225,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 1825. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable + ret.maxLateralAccel = 2.4 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_FORTE: @@ -244,6 +251,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.85 ret.steerRatio = 13.27 # 2021 Kia K5 Steering Ratio (all trims) tire_stiffness_factor = 0.5 + ret.maxLateralAccel = 2.1 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_EV6: @@ -254,8 +262,8 @@ class CarInterface(CarInterfaceBase): get_safety_config(car.CarParams.SafetyModel.hyundaiHDA2)] tire_stiffness_factor = 0.65 - max_lat_accel = 2. - set_torque_tune(ret.lateralTuning, max_lat_accel, 0.01) + ret.maxLateralAccel = 2. + set_torque_tune(ret.lateralTuning, ret.maxLateralAccel, 0.01) # Genesis elif candidate == CAR.GENESIS_G70: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 1ee237fe36..a2c11bf023 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,13 +1,14 @@ import os import time from abc import abstractmethod, ABC -from typing import Dict, Tuple, List +from typing import Any, Dict, Tuple, List from cereal import car +from common.basedir import BASEDIR +from common.conversions import Conversions as CV from common.kalman.simple_kalman import KF1D from common.realtime import DT_CTRL from selfdrive.car import gen_empty_fingerprint -from common.conversions import Conversions as CV from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -22,7 +23,6 @@ ACCEL_MIN = -3.5 # generic car and radar interfaces - class CarInterfaceBase(ABC): def __init__(self, CP, CarController, CarState): self.CP = CP @@ -81,6 +81,7 @@ class CarInterfaceBase(ABC): ret.steerControlType = car.CarParams.SteerControlType.torque ret.minSteerSpeed = 0. ret.wheelSpeedFactor = 1.0 + ret.maxLateralAccel = float('nan') ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this @@ -293,3 +294,31 @@ class CarStateBase(ABC): @staticmethod def get_loopback_can_parser(CP): return None + + +# interface-specific helpers + +def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: bool = False) -> Dict[str, Any]: + # read all the folders in selfdrive/car and return a dict where: + # - keys are all the car models or brand names + # - values are attr values from all car folders + result = {} + for car_folder in sorted([x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]): + try: + brand_name = car_folder.split('/')[-1] + brand_values = __import__(f'selfdrive.car.{brand_name}.values', fromlist=[attr]) + if hasattr(brand_values, attr) or not ignore_none: + attr_data = getattr(brand_values, attr, None) + else: + continue + + if combine_brands: + if isinstance(attr_data, dict): + for f, v in attr_data.items(): + result[f] = v + else: + result[brand_name] = attr_data + except (ImportError, OSError): + pass + + return result diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index 1209a8f1a1..becd66ba1f 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -132,7 +132,7 @@ class IsoTpParallelQuery: request_done[tx_addr] = True else: request_done[tx_addr] = True - cloudlog.warning(f"iso-tp query bad response: 0x{dat.hex()}") + cloudlog.warning(f"iso-tp query bad response: {tx_addr} - 0x{dat.hex()}") cur_time = time.monotonic() if cur_time - last_response_time > timeout: diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index d0d8e91ce1..edd26a4449 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -51,6 +51,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.5 ret.steerRatio = 17 # learned, 14 stock ret.steerActuatorDelay = 0.1 + ret.maxLateralAccel = 1.3 ret.lateralTuning.pid.kf = 0.00005 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] @@ -61,6 +62,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.5 ret.steerRatio = 17 # learned, 14 stock ret.steerActuatorDelay = 0.1 + ret.maxLateralAccel = 3.2 ret.lateralTuning.pid.kf = 0.000038 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 6e81fcb1b3..412333edcd 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -43,14 +43,14 @@ class SubaruCarInfo(CarInfo): CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-20"), CAR.IMPREZA: [ - SubaruCarInfo("Subaru Impreza 2017-19", good_torque=True), - SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26", good_torque=True), + SubaruCarInfo("Subaru Impreza 2017-19"), + SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), ], CAR.IMPREZA_2020: [ SubaruCarInfo("Subaru Impreza 2020-21"), SubaruCarInfo("Subaru Crosstrek 2020-21"), ], - CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-21", good_torque=True), + CAR.FORESTER: SubaruCarInfo("Subaru Forester 2019-21"), 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/tests/routes.py b/selfdrive/car/tests/routes.py index 27fdc9c705..d2ec6b68d7 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -26,7 +26,7 @@ non_tested_cars = [ HYUNDAI.KIA_OPTIMA_H, ] -TestRoute = namedtuple('TestRoute', ['route', 'car_fingerprint', 'segment'], defaults=(None,)) +TestRoute = namedtuple('TestRoute', ['route', 'car_model', 'segment'], defaults=(None,)) routes = [ TestRoute("efdf9af95e71cd84|2022-05-13--19-03-31", COMMA.BODY), diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index fcc90b9584..fed6989d40 100755 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -18,7 +18,7 @@ class TestCarDocs(unittest.TestCase): "Run selfdrive/car/docs.py to generate new supported cars documentation") def test_missing_car_info(self): - all_car_info_platforms = [p for i in get_interface_attr("CAR_INFO").values() for p in i] + all_car_info_platforms = get_interface_attr("CAR_INFO", combine_brands=True).keys() for platform in sorted(interfaces.keys()): if platform not in all_car_info_platforms: self.fail("Platform: {} doesn't exist in CarInfo".format(platform)) diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index ae209b2910..ed7e420e1a 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -4,9 +4,9 @@ import unittest from parameterized import parameterized from cereal import car -from selfdrive.car.car_helpers import interfaces +from selfdrive.car.car_helpers import get_interface_attr, interfaces from selfdrive.car.fingerprints import FW_VERSIONS -from selfdrive.car.fw_versions import match_fw_to_car +from selfdrive.car.fw_versions import REQUESTS, match_fw_to_car CarFw = car.CarParams.CarFw Ecu = car.CarParams.Ecu @@ -57,6 +57,23 @@ class TestFwFingerprint(unittest.TestCase): self.assertTrue(passed, "Blacklisted FW versions found") + def test_fw_request_ecu_whitelist(self): + passed = True + brands = set(r.brand for r in REQUESTS) + versions = get_interface_attr('FW_VERSIONS') + for brand in brands: + whitelisted_ecus = [ecu for r in REQUESTS for ecu in r.whitelist_ecus if r.brand == brand] + brand_ecus = set([fw[0] for car_fw in versions[brand].values() for fw in car_fw]) + + # each ecu in brand's fw versions needs to be whitelisted at least once + ecus_not_whitelisted = set(brand_ecus) - set(whitelisted_ecus) + if len(whitelisted_ecus) and len(ecus_not_whitelisted): + ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) + print(f'{brand.title()}: FW query whitelist missing ecus: {ecu_strings}') + passed = False + + self.assertTrue(passed, "Not all ecus in FW versions found in query whitelists") + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index d2867b9f4f..9ab881279b 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -18,6 +18,7 @@ from selfdrive.car.hyundai.values import CAR as HYUNDAI from selfdrive.car.tests.routes import non_tested_cars, routes, TestRoute from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader +from tools.lib.route import Route from panda.tests.safety import libpandasafety_py from panda.tests.safety.common import package_can_msg @@ -35,7 +36,7 @@ ignore_addr_checks_valid = [ # build list of test cases routes_by_car = defaultdict(set) for r in routes: - routes_by_car[r.car_fingerprint].add(r) + routes_by_car[r.car_model].add(r) test_cases: List[Tuple[str, Optional[TestRoute]]] = [] for i, c in enumerate(sorted(all_known_cars())): @@ -45,12 +46,17 @@ for i, c in enumerate(sorted(all_known_cars())): SKIP_ENV_VAR = "SKIP_LONG_TESTS" -@parameterized_class(('car_model', 'test_route'), test_cases) -class TestCarModel(unittest.TestCase): +class TestCarModelBase(unittest.TestCase): + car_model = None + test_route = None + ci = True @unittest.skipIf(SKIP_ENV_VAR in os.environ, f"Long running test skipped. Unset {SKIP_ENV_VAR} to run") @classmethod def setUpClass(cls): + if cls.__name__ == 'TestCarModel' or cls.__name__.endswith('Base'): + raise unittest.SkipTest + if cls.test_route is None: if cls.car_model in non_tested_cars: print(f"Skipping tests for {cls.car_model}: missing route") @@ -64,7 +70,10 @@ class TestCarModel(unittest.TestCase): for seg in test_segs: try: - lr = LogReader(get_url(cls.test_route.route, seg)) + if cls.ci: + lr = LogReader(get_url(cls.test_route.route, seg)) + else: + lr = LogReader(Route(cls.test_route.route).log_paths()[seg]) except Exception: continue @@ -79,6 +88,8 @@ class TestCarModel(unittest.TestCase): elif msg.which() == "carParams": if msg.carParams.openpilotLongitudinalControl: disable_radar = True + if cls.car_model is None and not cls.ci: + cls.car_model = msg.carParams.carFingerprint if len(can_msgs) > int(50 / DT_CTRL): break @@ -249,5 +260,10 @@ class TestCarModel(unittest.TestCase): self.assertFalse(len(failed_checks), f"panda safety doesn't agree with openpilot: {failed_checks}") +@parameterized_class(('car_model', 'test_route'), test_cases) +class TestCarModel(TestCarModelBase): + pass + + if __name__ == "__main__": unittest.main() diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 1b577cc6b7..a1ce8c4980 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -38,7 +38,8 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.74 # unknown end-to-end spec tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3045. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=1.7, FRICTION=0.06) + ret.maxLateralAccel = 1.7 + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06) elif candidate == CAR.PRIUS_V: stop_and_go = True @@ -46,7 +47,8 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.4 tire_stiffness_factor = 0.5533 ret.mass = 3340. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=1.8, FRICTION=0.06) + ret.maxLateralAccel = 1.8 + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06) elif candidate in (CAR.RAV4, CAR.RAV4H): stop_and_go = True if (candidate in CAR.RAV4H) else False @@ -54,14 +56,16 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.88 # 14.5 is spec end-to-end tire_stiffness_factor = 0.5533 ret.mass = 3650. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=1.8, FRICTION=0.06) + ret.maxLateralAccel = 1.8 + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.06) elif candidate == CAR.COROLLA: ret.wheelbase = 2.70 ret.steerRatio = 18.27 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 2860. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.8, FRICTION=0.024) + ret.maxLateralAccel = 2.8 + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.024) elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RXH, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2): stop_and_go = True @@ -70,6 +74,7 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.035 tire_stiffness_factor = 0.5533 ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max + ret.maxLateralAccel = 1.4 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.CHR, CAR.CHRH): @@ -78,6 +83,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.6 tire_stiffness_factor = 0.7933 ret.mass = 3300. * CV.LB_TO_KG + STD_CARGO_KG + ret.maxLateralAccel = 1.3 set_lat_tune(ret.lateralTuning, LatTunes.PID_F) elif candidate in (CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): @@ -87,8 +93,10 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid if candidate in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.4, FRICTION=0.05) + ret.maxLateralAccel = 2.4 + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.05) else: + ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): @@ -97,6 +105,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 ret.mass = 4700. * CV.LB_TO_KG + STD_CARGO_KG # 4260 + 4-5 people + ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_G) elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH): @@ -105,6 +114,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid limited + ret.maxLateralAccel = 1.8 set_lat_tune(ret.lateralTuning, LatTunes.PID_G) elif candidate in (CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019, CAR.AVALON_TSS2, CAR.AVALONH_TSS2): @@ -115,6 +125,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid + ret.maxLateralAccel = 1.6 set_lat_tune(ret.lateralTuning, LatTunes.PID_H) elif candidate in (CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022): @@ -123,6 +134,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.3 tire_stiffness_factor = 0.7933 ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid + ret.maxLateralAccel = 2.5 set_lat_tune(ret.lateralTuning, LatTunes.PID_D) # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. @@ -138,7 +150,8 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.9 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3060. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.0, FRICTION=0.07) + ret.maxLateralAccel = 2.0 + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=ret.maxLateralAccel, FRICTION=0.07) elif candidate in (CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_ESH): stop_and_go = True @@ -146,6 +159,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 # not optimized tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3677. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max + ret.maxLateralAccel = 2.2 set_lat_tune(ret.lateralTuning, LatTunes.PID_D) elif candidate == CAR.SIENNA: @@ -154,6 +168,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.5 tire_stiffness_factor = 0.444 ret.mass = 4590. * CV.LB_TO_KG + STD_CARGO_KG + ret.maxLateralAccel = 1.6 set_lat_tune(ret.lateralTuning, LatTunes.PID_J) elif candidate in (CAR.LEXUS_IS, CAR.LEXUS_RC): @@ -177,6 +192,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.7 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + STD_CARGO_KG + ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate == CAR.PRIUS_TSS2: @@ -185,6 +201,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.4 # True steerRatio from older prius tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3115. * CV.LB_TO_KG + STD_CARGO_KG + ret.maxLateralAccel = 2.0 set_lat_tune(ret.lateralTuning, LatTunes.PID_N) elif candidate == CAR.MIRAI: @@ -193,6 +210,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 tire_stiffness_factor = 0.8 ret.mass = 4300. * CV.LB_TO_KG + STD_CARGO_KG + ret.maxLateralAccel = 2.4 set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.ALPHARD_TSS2, CAR.ALPHARDH_TSS2): diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 811b3a6e1b..e97ed6b056 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -50,7 +50,7 @@ def set_long_tune(tune, name): ###### LAT ###### -def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=.1, use_steering_angle=True): +def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, use_steering_angle=True): if name == LatTunes.TORQUE: set_torque_tune(tune, MAX_LAT_ACCEL, FRICTION) elif 'PID' in str(name): diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0b6948cf44..3204d36b5a 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -100,7 +100,6 @@ class Footnote(Enum): @dataclass class ToyotaCarInfo(CarInfo): package: str = "All" - good_torque: bool = True harness: Enum = Harness.toyota diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 3a0d7c8ce8..90bbd6d889 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -64,14 +64,17 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.ATLAS_MK1: ret.mass = 2011 + STD_CARGO_KG ret.wheelbase = 2.98 + ret.maxLateralAccel = 1.4 elif candidate == CAR.GOLF_MK7: ret.mass = 1397 + STD_CARGO_KG ret.wheelbase = 2.62 + ret.maxLateralAccel = 1.5 elif candidate == CAR.JETTA_MK7: ret.mass = 1328 + STD_CARGO_KG ret.wheelbase = 2.71 + ret.maxLateralAccel = 1.2 elif candidate == CAR.PASSAT_MK8: ret.mass = 1551 + STD_CARGO_KG @@ -92,6 +95,7 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.TIGUAN_MK2: ret.mass = 1715 + STD_CARGO_KG ret.wheelbase = 2.74 + ret.maxLateralAccel = 1.1 elif candidate == CAR.TOURAN_MK2: ret.mass = 1516 + STD_CARGO_KG @@ -109,6 +113,7 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.AUDI_A3_MK3: ret.mass = 1335 + STD_CARGO_KG ret.wheelbase = 2.61 + ret.maxLateralAccel = 1.7 elif candidate == CAR.AUDI_Q2_MK1: ret.mass = 1205 + STD_CARGO_KG @@ -117,6 +122,7 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.AUDI_Q3_MK2: ret.mass = 1623 + STD_CARGO_KG ret.wheelbase = 2.68 + ret.maxLateralAccel = 1.6 elif candidate == CAR.SEAT_ATECA_MK1: ret.mass = 1900 + STD_CARGO_KG diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 6367dd8969..44743c948e 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -135,7 +135,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { VWCarInfo("Volkswagen Jetta 2018-21"), VWCarInfo("Volkswagen Jetta GLI 2021"), ], - CAR.PASSAT_MK8: VWCarInfo("Volkswagen Passat 2015-18", footnotes=[Footnote.PASSAT]), + CAR.PASSAT_MK8: VWCarInfo("Volkswagen Passat 2015-19", footnotes=[Footnote.PASSAT]), CAR.POLO_MK6: VWCarInfo("Volkswagen Polo 2020"), 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), @@ -445,6 +445,7 @@ FW_VERSIONS = { b'\xf1\x873G0906264 \xf1\x890004', ], (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300043H \xf1\x891601', b'\xf1\x870CW300048R \xf1\x890610', b'\xf1\x870D9300014L \xf1\x895002', b'\xf1\x870D9300041A \xf1\x894801', @@ -456,6 +457,7 @@ FW_VERSIONS = { b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\0165915005914001344701311442900', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\02315120011111200631145171716121691132111', ], (Ecu.eps, 0x712, None): [ @@ -464,11 +466,13 @@ FW_VERSIONS = { b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521B00606A1', b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\00516B00501A1', b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521B00703A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x873Q0907572A \xf1\x890130', b'\xf1\x873Q0907572B \xf1\x890192', b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x873Q0907572C \xf1\x890196', b'\xf1\x875Q0907572R \xf1\x890771', ], }, diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 4afa8d89ed..91981259aa 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -97,26 +97,27 @@ def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): psis = [0.0]*CONTROL_N curvatures = [0.0]*CONTROL_N curvature_rates = [0.0]*CONTROL_N - + v_ego = max(v_ego, 0.1) + # TODO this needs more thought, use .2s extra for now to estimate other delays delay = CP.steerActuatorDelay + .2 - current_curvature = curvatures[0] - psi = interp(delay, T_IDXS[:CONTROL_N], psis) - desired_curvature_rate = curvature_rates[0] - + # MPC can plan to turn the wheel and turn back before t_delay. This means # in high delay cases some corrections never even get commanded. So just use # psi to calculate a simple linearization of desired curvature - curvature_diff_from_psi = psi / (max(v_ego, 1e-1) * delay) - current_curvature - desired_curvature = current_curvature + 2 * curvature_diff_from_psi - - v_ego = max(v_ego, 0.1) + current_curvature_desired = curvatures[0] + psi = interp(delay, T_IDXS[:CONTROL_N], psis) + average_curvature_desired = psi / (v_ego * delay) + desired_curvature = 2 * average_curvature_desired - current_curvature_desired + + # This is the "desired rate of the setpoint" not an actual desired rate + desired_curvature_rate = curvature_rates[0] max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) safe_desired_curvature_rate = clip(desired_curvature_rate, -max_curvature_rate, max_curvature_rate) safe_desired_curvature = clip(desired_curvature, - current_curvature - max_curvature_rate * DT_MDL, - current_curvature + max_curvature_rate * DT_MDL) + current_curvature_desired - max_curvature_rate * DT_MDL, + current_curvature_desired + max_curvature_rate * DT_MDL) return safe_desired_curvature, safe_desired_curvature_rate diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index b5041eb172..79c881d11b 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -78,6 +78,7 @@ class LatControlINDI(LatControl): steers_des += math.radians(params.angleOffsetDeg) indi_log.steeringAngleDesiredDeg = math.degrees(steers_des) + # desired rate is the desired rate of change in the setpoint, not the absolute desired curvature rate_des = VM.get_steer_from_curvature(-desired_curvature_rate, CS.vEgo, 0) indi_log.steeringRateDesiredDeg = math.degrees(rate_des) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 820862af9e..47f0b69f2b 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -22,7 +22,7 @@ LOW_SPEED_FACTOR = 200 JERK_THRESHOLD = 0.2 -def set_torque_tune(tune, MAX_LAT_ACCEL=2.5, FRICTION=.1): +def set_torque_tune(tune, MAX_LAT_ACCEL=2.5, FRICTION=0.01): tune.init('torque') tune.torque.useSteeringAngle = True tune.torque.kp = 1.0 / MAX_LAT_ACCEL @@ -59,6 +59,8 @@ class LatControlTorque(LatControl): actual_curvature_llk = llk.angularVelocityCalibrated.value[2] / CS.vEgo actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_llk]) desired_lateral_accel = desired_curvature * CS.vEgo ** 2 + + # desired rate is the desired rate of change in the setpoint, not the absolute desired curvature desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2 actual_lateral_accel = actual_curvature * CS.vEgo ** 2 diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 6349f05cc2..f3f59ee308 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -79,6 +79,9 @@ class LateralPlanner: y_pts, heading_pts) # init state for next + # mpc.u_sol is the desired curvature rate given x0 curv state. + # with x0[3] = measured_curvature, this would be the actual desired rate. + # instead, interpolate x_sol so that x0[3] is the desired curvature for lat_control. self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3]) # Check for infeasible MPC solution diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 1fc79decef..083aeb79cc 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -16,7 +16,7 @@ def plannerd_thread(sm=None, pm=None): CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) - use_lanelines = not params.get_bool('EndToEndToggle') + use_lanelines = False wide_camera = params.get_bool('WideCameraOnly') cloudlog.event("e2e mode", on=use_lanelines) diff --git a/selfdrive/debug/test_car_model.py b/selfdrive/debug/test_car_model.py new file mode 100755 index 0000000000..9082dbe3d6 --- /dev/null +++ b/selfdrive/debug/test_car_model.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python3 +import argparse +import sys +from typing import List, Tuple +import unittest + +from selfdrive.car.tests.routes import TestRoute +from selfdrive.car.tests.test_models import TestCarModel + + +def create_test_models_suite(routes: List[Tuple[str, TestRoute]], ci=False) -> unittest.TestSuite: + test_suite = unittest.TestSuite() + for car_model, test_route in routes: + # create new test case and discover tests + test_case_args = {"car_model": car_model, "test_route": test_route, "ci": ci} + CarModelTestCase = type("CarModelTestCase", (TestCarModel,), test_case_args) + test_suite.addTest(unittest.TestLoader().loadTestsFromTestCase(CarModelTestCase)) + return test_suite + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Test any route against common issues with a new car port. " + + "Uses selfdrive/car/tests/test_models.py") + parser.add_argument("route", help="Specify route to run tests on") + parser.add_argument("--car", help="Specify car model for test route") + parser.add_argument("--segment", type=int, nargs="?", help="Specify segment of route to test") + parser.add_argument("--ci", action="store_true", help="Attempt to get logs using openpilotci, need to specify car") + args = parser.parse_args() + if len(sys.argv) == 1: + parser.print_help() + sys.exit() + + test_route = TestRoute(args.route, args.car, segment=args.segment) + test_suite = create_test_models_suite([(args.car, test_route)], ci=args.ci) + + unittest.TextTestRunner().run(test_suite) diff --git a/selfdrive/hardware/tici/agnos.json b/selfdrive/hardware/tici/agnos.json index 6674ddaa5b..004a0f9dfb 100644 --- a/selfdrive/hardware/tici/agnos.json +++ b/selfdrive/hardware/tici/agnos.json @@ -1,10 +1,10 @@ [ { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-0a86272196cb54607f8ba082f412fed4607baaf6ce3eb8dc8e950b4a1d763954.img.xz", - "hash": "0a86272196cb54607f8ba082f412fed4607baaf6ce3eb8dc8e950b4a1d763954", - "hash_raw": "0a86272196cb54607f8ba082f412fed4607baaf6ce3eb8dc8e950b4a1d763954", - "size": 14776320, + "url": "https://commadist.azureedge.net/agnosupdate/boot-bb71f49294150c4233b89e2a10768a5a3de003203ecd02e3f845821b35cd409f.img.xz", + "hash": "bb71f49294150c4233b89e2a10768a5a3de003203ecd02e3f845821b35cd409f", + "hash_raw": "bb71f49294150c4233b89e2a10768a5a3de003203ecd02e3f845821b35cd409f", + "size": 14780416, "sparse": false, "full_check": true, "has_ab": true @@ -41,9 +41,9 @@ }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-9b0b534ed0c35c25850dbb73d3f052611f2e2c9db32410edc25d75fbcfc6c15e.img.xz", - "hash": "b1f622f00037bbdb28c0a6016c0e42fa7f87e99591ff2417c757a67ff559b526", - "hash_raw": "9b0b534ed0c35c25850dbb73d3f052611f2e2c9db32410edc25d75fbcfc6c15e", + "url": "https://commadist.azureedge.net/agnosupdate/system-11fdbc9e8a9cd27f98346d7e1039bc5b3032d0e892ff95fa1258673ff1809bca.img.xz", + "hash": "45b4719a9e580617cf840036b24fb0dcd32491edd9654d8d74c28d91ff362d36", + "hash_raw": "11fdbc9e8a9cd27f98346d7e1039bc5b3032d0e892ff95fa1258673ff1809bca", "size": 10737418240, "sparse": true, "full_check": false, diff --git a/selfdrive/hardware/tici/test_power_draw.py b/selfdrive/hardware/tici/test_power_draw.py index 03ee390b61..5eb84514e5 100755 --- a/selfdrive/hardware/tici/test_power_draw.py +++ b/selfdrive/hardware/tici/test_power_draw.py @@ -16,11 +16,11 @@ class Proc: power: float rtol: float = 0.05 atol: float = 0.1 - warmup: float = 3. + warmup: float = 6. PROCS = [ - Proc('camerad', 2.25), - Proc('modeld', 0.95), + Proc('camerad', 2.15), + Proc('modeld', 1.0), Proc('dmonitoringmodeld', 0.35), Proc('encoderd', 0.23), ] diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index dae359b905..f0c52e7e03 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -1,14 +1,16 @@ #!/usr/bin/env python3 -from typing import List +import time +from multiprocessing import Process, Queue +from typing import List, Optional import numpy as np from collections import defaultdict -from numpy.linalg import linalg - from cereal import log, messaging from laika import AstroDog -from laika.ephemeris import convert_ublox_ephem +from laika.constants import SECS_IN_MIN +from laika.ephemeris import EphemerisType, convert_ublox_ephem +from laika.gps_time import GPSTime from laika.helpers import ConstellationId from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind @@ -22,48 +24,54 @@ MAX_TIME_GAP = 10 class Laikad: - def __init__(self, use_internet): - self.astro_dog = AstroDog(use_internet=use_internet) + def __init__(self, valid_const=("GPS", "GLONASS"), auto_update=False, valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV)): + self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types) self.gnss_kf = GNSSKalman(GENERATED_DIR) + self.orbit_p: Optional[Process] = None + self.orbit_q = Queue() def process_ublox_msg(self, ublox_msg, ublox_mono_time: int): if ublox_msg.which == 'measurementReport': report = ublox_msg.measurementReport + if report.gpsWeek > 0: + latest_msg_t = GPSTime(report.gpsWeek, report.rcvTow) + self.fetch_orbits(latest_msg_t + SECS_IN_MIN, block=False) new_meas = read_raw_ublox(report) + measurements = process_measurements(new_meas, self.astro_dog) pos_fix = calc_pos_fix(measurements, min_measurements=4) # To get a position fix a minimum of 5 measurements are needed. # Each report can contain less and some measurements can't be processed. corrected_measurements = [] - if len(pos_fix) > 0 and linalg.norm(pos_fix[1]) < 100: + if len(pos_fix) > 0 and abs(np.array(pos_fix[1])).mean() < 1000: corrected_measurements = correct_measurements(measurements, pos_fix[0][:3], self.astro_dog) t = ublox_mono_time * 1e-9 self.update_localizer(pos_fix, t, corrected_measurements) localizer_valid = self.localizer_valid(t) + ecef_pos = self.gnss_kf.x[GStates.ECEF_POS].tolist() ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist() - pos_std = float(np.linalg.norm(self.gnss_kf.P[GStates.ECEF_POS])) - vel_std = float(np.linalg.norm(self.gnss_kf.P[GStates.ECEF_VELOCITY])) + pos_std = self.gnss_kf.P[GStates.ECEF_POS].flatten().tolist() + vel_std = self.gnss_kf.P[GStates.ECEF_VELOCITY].flatten().tolist() bearing_deg, bearing_std = get_bearing_from_gnss(ecef_pos, ecef_vel, vel_std) meas_msgs = [create_measurement_msg(m) for m in corrected_measurements] - dat = messaging.new_message("gnssMeasurements") - measurement_msg = log.GnssMeasurements.Measurement.new_message + measurement_msg = log.LiveLocationKalman.Measurement.new_message dat.gnssMeasurements = { "positionECEF": measurement_msg(value=ecef_pos, std=pos_std, valid=localizer_valid), "velocityECEF": measurement_msg(value=ecef_vel, std=vel_std, valid=localizer_valid), - "bearingDeg": measurement_msg(value=[bearing_deg], std=bearing_std, valid=localizer_valid), + "bearingDeg": measurement_msg(value=[bearing_deg], std=[bearing_std], valid=localizer_valid), "ubloxMonoTime": ublox_mono_time, "correctedMeasurements": meas_msgs } return dat elif ublox_msg.which == 'ephemeris': ephem = convert_ublox_ephem(ublox_msg.ephemeris) - self.astro_dog.add_ephem(ephem, self.astro_dog.orbits) + self.astro_dog.add_ephems([ephem], self.astro_dog.nav) # elif ublox_msg.which == 'ionoData': # todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them. @@ -77,7 +85,7 @@ class Laikad: filter_time = self.gnss_kf.filter.filter_time if filter_time is None: cloudlog.info("Init gnss kalman filter") - elif (t - filter_time) > MAX_TIME_GAP: + elif abs(t - filter_time) > MAX_TIME_GAP: cloudlog.error("Time gap of over 10s detected, gnss kalman reset") else: cloudlog.error("Gnss kalman filter state is nan") @@ -90,8 +98,7 @@ class Laikad: def localizer_valid(self, t: float): filter_time = self.gnss_kf.filter.filter_time - return filter_time is not None and (t - filter_time) < MAX_TIME_GAP and \ - all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS])) + return filter_time is not None and (t - filter_time) < MAX_TIME_GAP and all(np.isfinite(self.gnss_kf.x[GStates.ECEF_POS])) def init_gnss_localizer(self, est_pos): x_initial, p_initial_diag = np.copy(GNSSKalman.x_initial), np.copy(np.diagonal(GNSSKalman.P_initial)) @@ -100,6 +107,29 @@ class Laikad: self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag) + def get_orbit_data(self, t: GPSTime, queue): + cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}") + start_time = time.monotonic() + self.astro_dog.get_orbit_data(t, only_predictions=True) + cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.2f}s") + queue.put((self.astro_dog.orbits, self.astro_dog.orbit_fetched_times)) + + def fetch_orbits(self, t: GPSTime, block): + if t not in self.astro_dog.orbit_fetched_times: + if self.orbit_p is None: + self.orbit_p = Process(target=self.get_orbit_data, args=(t, self.orbit_q)) + self.orbit_p.start() + ret = None + if block: + ret = self.orbit_q.get(block=True) + elif not self.orbit_q.empty(): + ret = self.orbit_q.get() + + if ret: + self.astro_dog.orbits, self.astro_dog.orbit_fetched_times = ret + self.orbit_p.join() + self.orbit_p = None + def create_measurement_msg(meas: GNSSMeasurement): c = log.GnssMeasurements.CorrectedMeasurement.new_message() @@ -136,7 +166,7 @@ def get_bearing_from_gnss(ecef_pos, ecef_vel, vel_std): ned_vel = np.einsum('ij,j ->i', converter.ned_from_ecef_matrix, ecef_vel) bearing = np.arctan2(ned_vel[1], ned_vel[0]) - bearing_std = np.arctan2(vel_std, np.linalg.norm(ned_vel)) + bearing_std = np.arctan2(np.linalg.norm(vel_std), np.linalg.norm(ned_vel)) return float(np.rad2deg(bearing)), float(bearing_std) @@ -144,8 +174,7 @@ def main(): sm = messaging.SubMaster(['ubloxGnss']) pm = messaging.PubMaster(['gnssMeasurements']) - laikad = Laikad(use_internet=True) - + laikad = Laikad() while True: sm.update() diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index bf984becb8..630a7525eb 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -2,9 +2,10 @@ import unittest from datetime import datetime +from laika.ephemeris import EphemerisType from laika.gps_time import GPSTime from laika.helpers import ConstellationId -from laika.raw_gnss import GNSSMeasurement +from laika.raw_gnss import GNSSMeasurement, read_raw_ublox from selfdrive.locationd.laikad import Laikad, create_measurement_msg from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader @@ -17,11 +18,11 @@ def get_log(segs=range(0)): return [m for m in logs if m.which() == 'ubloxGnss'] -def process_msgs(lr, laikad: Laikad): +def verify_messages(lr, laikad): good_msgs = [] for m in lr: msg = laikad.process_ublox_msg(m.ubloxGnss, m.logMonoTime) - if msg is not None: + if msg is not None and len(msg.gnssMeasurements.correctedMeasurements) > 0: good_msgs.append(msg) return good_msgs @@ -42,32 +43,59 @@ class TestLaikad(unittest.TestCase): self.assertEqual(msg.constellationId, 'gps') def test_laika_online(self): - # Set to offline forces to use ephemeris messages - laikad = Laikad(use_internet=True) - msgs = process_msgs(self.logs, laikad) - correct_msgs = [m for m in msgs if len(m.gnssMeasurements.correctedMeasurements) > 0] + laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT) + correct_msgs = verify_messages(self.logs, laikad) + + correct_msgs_expected = 560 + self.assertEqual(correct_msgs_expected, len(correct_msgs)) + self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) + + def test_laika_online_nav_only(self): + laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.NAV) + correct_msgs = verify_messages(self.logs, laikad) correct_msgs_expected = 560 self.assertEqual(correct_msgs_expected, len(correct_msgs)) self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) def test_laika_offline(self): - # Set to offline forces to use ephemeris messages - laikad = Laikad(use_internet=False) - msgs = process_msgs(self.logs, laikad) - correct_msgs = [m for m in msgs if len(m.gnssMeasurements.correctedMeasurements) > 0] + # Set auto_update to false forces to use ephemeris messages + laikad = Laikad(auto_update=False) + correct_msgs = verify_messages(self.logs, laikad) self.assertEqual(256, len(correct_msgs)) self.assertEqual(256, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) def test_laika_offline_ephem_at_start(self): # Test offline but process ephemeris msgs of segment first - laikad = Laikad(use_internet=False) + laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.NAV) ephemeris_logs = [m for m in self.logs if m.ubloxGnss.which() == 'ephemeris'] - msgs = process_msgs(ephemeris_logs+self.logs, laikad) - correct_msgs = [m for m in msgs if len(m.gnssMeasurements.correctedMeasurements) > 0] + correct_msgs = verify_messages(ephemeris_logs+self.logs, laikad) + self.assertEqual(554, len(correct_msgs)) self.assertGreaterEqual(554, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) + def test_laika_get_orbits(self): + laikad = Laikad(auto_update=False) + first_gps_time = None + for m in self.logs: + if m.ubloxGnss.which == 'measurementReport': + new_meas = read_raw_ublox(m.ubloxGnss.measurementReport) + if len(new_meas) != 0: + first_gps_time = new_meas[0].recv_time + break + # Pretend process has loaded the orbits on startup by using the time of the first gps message. + laikad.fetch_orbits(first_gps_time, block=True) + self.assertEqual(29, len(laikad.astro_dog.orbits.keys())) + + @unittest.skip("Use to debug live data") + def test_laika_get_orbits_now(self): + laikad = Laikad(auto_update=False) + laikad.fetch_orbits(GPSTime.from_datetime(datetime.utcnow()), block=True) + prn = "G01" + self.assertLess(0, len(laikad.astro_dog.orbits[prn])) + prn = "R01" + self.assertLess(0, len(laikad.astro_dog.orbits[prn])) + print(min(laikad.astro_dog.orbits[prn], key=lambda e: e.epoch).epoch.as_datetime()) if __name__ == "__main__": unittest.main() diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index bcc62a2932..8421605a55 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -17,7 +17,7 @@ from selfdrive.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") -TOTAL_SCONS_NODES = 2405 +TOTAL_SCONS_NODES = 2035 MAX_BUILD_PROGRESS = 100 PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 48524aec1d..5d996d1169 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -21,13 +21,13 @@ procs = [ DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), # due to qualcomm kernel bugs SIGKILLing camerad sometimes causes page table corruption NativeProcess("camerad", "selfdrive/camerad", ["./camerad"], unkillable=True, callback=driverview), - NativeProcess("clocksd", "selfdrive/clocksd", ["./clocksd"]), + NativeProcess("clocksd", "system/clocksd", ["./clocksd"]), NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), callback=driverview), - NativeProcess("logcatd", "selfdrive/logcatd", ["./logcatd"]), + NativeProcess("logcatd", "system/logcatd", ["./logcatd"]), NativeProcess("encoderd", "selfdrive/loggerd", ["./encoderd"]), NativeProcess("loggerd", "selfdrive/loggerd", ["./loggerd"], onroad=False, callback=logging), NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]), - NativeProcess("proclogd", "selfdrive/proclogd", ["./proclogd"]), + NativeProcess("proclogd", "system/proclogd", ["./proclogd"]), NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC), NativeProcess("ubloxd", "selfdrive/locationd", ["./ubloxd"], enabled=(not PC or WEBCAM)), NativeProcess("ui", "selfdrive/ui", ["./ui"], offroad=True, watchdog_max_dt=(5 if not PC else None)), diff --git a/selfdrive/modeld/models/README.md b/selfdrive/modeld/models/README.md index a0cdd7967e..6b704cbfa8 100644 --- a/selfdrive/modeld/models/README.md +++ b/selfdrive/modeld/models/README.md @@ -23,64 +23,8 @@ To view the architecture of the ONNX networks, you can use [netron](https://netr * The recurrent state vector that is fed back into the GRU for temporal context : 512 -### Supercombo output format (Full size: 6472 x float32) -* **plan** - * 5 potential desired plan predictions : 4955 = 5 * 991 - * predicted mean and standard deviation of the following values at 33 timesteps : 990 = 2 * 33 * 15 - * x,y,z position in current frame (meters) - * x,y,z velocity in local frame (meters/s) - * x,y,z acceleration local frame (meters/(s*s)) - * roll, pitch , yaw in current frame (radians) - * roll, pitch , yaw rates in local frame (radians/s) - * probability[^1] of this plan hypothesis being the most likely: 1 -* **lanelines** - * 4 lanelines (outer left, left, right, and outer right): 528 = 4 * 132 - * predicted mean and standard deviation for the following values at 33 x positions : 132 = 2 * 33 * 2 - * y position in current frame (meters) - * z position in current frame (meters) -* **laneline probabilties** - * 2 probabilities[^1] that each of the 4 lanelines exists : 8 = 4 * 2 - * deprecated probability - * used probability -* **road-edges** - * 2 road-edges (left and right): 264 = 2 * 132 - * predicted mean and standard deviation for the following values at 33 x positions : 132 = 2 * 33 * 2 - * y position in current frame (meters) - * z position in current frame (meters) -* **leads** - * 2 hypotheses for potential lead cars : 102 = 2 * 51 - * predicted mean and stadard deviation for the following values at 0,2,4,6,8,10s : 48 = 2 * 6 * 4 - * x position of lead in current frame (meters) - * y position of lead in current frame (meters) - * speed of lead (meters/s) - * acceleration of lead(meters/(s*s)) - * probabilities[^1] this hypothesis is the most likely hypothesis at 0s, 2s or 4s from now : 3 -* **lead probabilities** - * probability[^1] that there is a lead car at 0s, 2s, 4s from now : 3 = 1 * 3 -* **desire state** - * probability[^1] that the model thinks it is executing each of the 8 potential desire actions : 8 -* **meta** [^2] - * Various metadata about the scene : 80 = 1 + 35 + 12 + 32 - * Probability[^1] that openpilot is engaged : 1 - * Probabilities[^1] of various things happening between now and 2,4,6,8,10s : 35 = 5 * 7 - * Disengage of openpilot with gas pedal - * Disengage of openpilot with brake pedal - * Override of openpilot steering - * 3m/(s*s) of deceleration - * 4m/(s*s) of deceleration - * 5m/(s*s) of deceleration - * Probabilities[^1] of left or right blinker being active at 0,2,4,6,8,10s : 12 = 6 * 2 - * Probabilities[^1] that each of the 8 desires is being executed at 0,2,4,6s : 32 = 4 * 8 - -* **pose** [^2] - * predicted mean and standard deviation of current translation and rotation rates : 12 = 2 * 6 - * x,y,z velocity in current frame (meters/s) - * roll, pitch , yaw rates in current frame (radians/s) -* **recurrent state** - * The recurrent state vector that is fed back into the GRU for temporal context : 512 - -[^1]: All probabilities are in logits, so you need to apply sigmoid or softmax functions to get actual probabilities -[^2]: These outputs come directly from the vision blocks, they do not have access to temporal state or the desire input +### Supercombo output format (Full size: XXX x float32) +Read [here](https://github.com/commaai/openpilot/blob/90af436a121164a51da9fa48d093c29f738adf6a/selfdrive/modeld/models/driving.h#L236) for more. ## Driver Monitoring Model diff --git a/selfdrive/modeld/runners/onnx_runner.py b/selfdrive/modeld/runners/onnx_runner.py index 2a6238c1d2..e282a66b66 100755 --- a/selfdrive/modeld/runners/onnx_runner.py +++ b/selfdrive/modeld/runners/onnx_runner.py @@ -59,7 +59,10 @@ if __name__ == "__main__": options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_ENABLE_ALL provider = 'CPUExecutionProvider' - print("Onnx selected provider: ", [provider], file=sys.stderr) - ort_session = ort.InferenceSession(sys.argv[1], options, providers=[provider]) - print("Onnx using ", ort_session.get_providers(), file=sys.stderr) - run_loop(ort_session) + try: + print("Onnx selected provider: ", [provider], file=sys.stderr) + ort_session = ort.InferenceSession(sys.argv[1], options, providers=[provider]) + print("Onnx using ", ort_session.get_providers(), file=sys.stderr) + run_loop(ort_session) + except KeyboardInterrupt: + pass diff --git a/selfdrive/navd/helpers.py b/selfdrive/navd/helpers.py index 89fd5e7e4e..eda813154a 100644 --- a/selfdrive/navd/helpers.py +++ b/selfdrive/navd/helpers.py @@ -2,18 +2,24 @@ from __future__ import annotations import json import math -from typing import Any, Dict, List, Optional, Tuple +from typing import Any, Dict, List, Optional, Tuple, Union, cast +from common.conversions import Conversions from common.numpy_fast import clip from common.params import Params EARTH_MEAN_RADIUS = 6371007.2 +SPEED_CONVERSIONS = { + 'km/h': Conversions.KPH_TO_MS, + 'mph': Conversions.MPH_TO_MS, + } class Coordinate: def __init__(self, latitude: float, longitude: float) -> None: self.latitude = latitude self.longitude = longitude + self.annotations: Dict[str, float] = {} @classmethod def from_mapbox_tuple(cls, t: Tuple[float, float]) -> Coordinate: @@ -116,6 +122,12 @@ def string_to_direction(direction: str) -> str: return 'none' +def maxspeed_to_ms(maxspeed: Dict[str, Union[str, float]]) -> float: + unit = cast(str, maxspeed['unit']) + speed = cast(float, maxspeed['speed']) + return SPEED_CONVERSIONS[unit] * speed + + def parse_banner_instructions(instruction: Any, banners: Any, distance_to_maneuver: float = 0.0) -> None: if not len(banners): return diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index 0a8eab7e06..52db9b1d08 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -10,11 +10,11 @@ from cereal import log from common.api import Api from common.params import Params from common.realtime import Ratekeeper -from selfdrive.swaglog import cloudlog from selfdrive.navd.helpers import (Coordinate, coordinate_from_param, - distance_along_geometry, + distance_along_geometry, maxspeed_to_ms, minimum_distance, parse_banner_instructions) +from selfdrive.swaglog import cloudlog REROUTE_DISTANCE = 25 MANEUVER_TRANSITION_THRESHOLD = 10 @@ -110,7 +110,7 @@ class RouteEngine: params = { 'access_token': self.mapbox_token, - # 'annotations': 'maxspeed', + 'annotations': 'maxspeed', 'geometries': 'geojson', 'overview': 'full', 'steps': 'true', @@ -131,9 +131,25 @@ class RouteEngine: self.route = r['routes'][0]['legs'][0]['steps'] self.route_geometry = [] + maxspeed_idx = 0 + maxspeeds = r['routes'][0]['legs'][0]['annotation']['maxspeed'] + # Convert coordinates for step in self.route: - self.route_geometry.append([Coordinate.from_mapbox_tuple(c) for c in step['geometry']['coordinates']]) + coords = [] + + for c in step['geometry']['coordinates']: + coord = Coordinate.from_mapbox_tuple(c) + + # Last step does not have maxspeed + if (maxspeed_idx < len(maxspeeds)) and ('unknown' not in maxspeeds[maxspeed_idx]): + coord.annotations['maxspeed'] = maxspeed_to_ms(maxspeeds[maxspeed_idx]) + + coords.append(coord) + maxspeed_idx += 1 + + self.route_geometry.append(coords) + maxspeed_idx -= 1 # Every segment ends with the same coordinate as the start of the next self.step_idx = 0 else: @@ -179,6 +195,23 @@ class RouteEngine: msg.navInstruction.timeRemaining = total_time msg.navInstruction.timeRemainingTypical = total_time_typical + # Speed limit + closest_idx, closest = min(enumerate(geometry), key=lambda p: p[1].distance_to(self.last_position)) + if closest_idx > 0: + # If we are not past the closest point, show previous + if along_geometry < distance_along_geometry(geometry, geometry[closest_idx]): + closest = geometry[closest_idx - 1] + + if 'maxspeed' in closest.annotations: + msg.navInstruction.speedLimit = closest.annotations['maxspeed'] + + # Speed limit sign type + if 'speedLimitSign' in step: + if step['speedLimitSign'] == 'mutcd': + msg.navInstruction.speedLimitSign = log.NavInstruction.SpeedLimitSign.mutcd + elif step['speedLimitSign'] == 'vienna': + msg.navInstruction.speedLimitSign = log.NavInstruction.SpeedLimitSign.vienna + self.pm.send('navInstruction', msg) # Transition to next route segment diff --git a/selfdrive/test/process_replay/helpers.py b/selfdrive/test/process_replay/helpers.py index b650ecb69a..8571f36c36 100644 --- a/selfdrive/test/process_replay/helpers.py +++ b/selfdrive/test/process_replay/helpers.py @@ -23,4 +23,4 @@ class OpenpilotPrefix(object): os.remove(symlink_path) shutil.rmtree(self.msgq_path, ignore_errors=True) del os.environ['OPENPILOT_PREFIX'] - return True + return False diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 630752d81e..032b504879 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -10,9 +10,8 @@ import cereal.messaging as messaging from cereal.visionipc import VisionIpcServer, VisionStreamType from common.spinner import Spinner from common.timeout import Timeout -from common.transformations.camera import get_view_frame_from_road_frame, eon_f_frame_size, tici_f_frame_size, \ - eon_d_frame_size, tici_d_frame_size -from selfdrive.hardware import PC, TICI +from common.transformations.camera import get_view_frame_from_road_frame, tici_f_frame_size, tici_d_frame_size +from selfdrive.hardware import PC from selfdrive.manager.process_config import managed_processes from selfdrive.test.openpilotci import BASE_URL, get_url from selfdrive.test.process_replay.compare_logs import compare_logs, save_log @@ -23,14 +22,14 @@ from tools.lib.logreader import LogReader TEST_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36" SEGMENT = 0 +MAX_FRAMES = 20 if PC else 1300 SEND_EXTRA_INPUTS = bool(os.getenv("SEND_EXTRA_INPUTS", "0")) VIPC_STREAM = {"roadCameraState": VisionStreamType.VISION_STREAM_ROAD, "driverCameraState": VisionStreamType.VISION_STREAM_DRIVER, "wideRoadCameraState": VisionStreamType.VISION_STREAM_WIDE_ROAD} - -def get_log_fn(ref_commit, test_route, tici=True): - return f"{test_route}_{'model_tici' if tici else 'model'}_{ref_commit}.bz2" +def get_log_fn(ref_commit, test_route): + return f"{test_route}_model_tici_{ref_commit}.bz2" def replace_calib(msg, calib): @@ -41,12 +40,15 @@ def replace_calib(msg, calib): def model_replay(lr, frs): - spinner = Spinner() - spinner.update("starting model replay") + if not PC: + spinner = Spinner() + spinner.update("starting model replay") + else: + spinner = None vipc_server = VisionIpcServer("camerad") - vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, False, *(tici_f_frame_size if TICI else eon_f_frame_size)) - vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, *(tici_d_frame_size if TICI else eon_d_frame_size)) + vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, False, *(tici_f_frame_size)) + vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, *(tici_d_frame_size)) vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, *(tici_f_frame_size)) vipc_server.start_listener() @@ -76,7 +78,7 @@ def model_replay(lr, frs): for cam_msgs in zip_longest(msgs['roadCameraState'], msgs['wideRoadCameraState'], msgs['driverCameraState']): # need a pair of road/wide msgs - if TICI and None in (cam_msgs[0], cam_msgs[1]): + if None in (cam_msgs[0], cam_msgs[1]): break for msg in cam_msgs: @@ -107,7 +109,7 @@ def model_replay(lr, frs): recv = None if msg.which() in ('roadCameraState', 'wideRoadCameraState'): - if not TICI or min(frame_idxs['roadCameraState'], frame_idxs['wideRoadCameraState']) > recv_cnt['modelV2']: + if min(frame_idxs['roadCameraState'], frame_idxs['wideRoadCameraState']) > recv_cnt['modelV2']: recv = "modelV2" elif msg.which() == 'driverCameraState': recv = "driverStateV2" @@ -118,14 +120,19 @@ def model_replay(lr, frs): recv_cnt[recv] += 1 log_msgs.append(messaging.recv_one(sm.sock[recv])) - spinner.update("replaying models: road %d/%d, driver %d/%d" % (frame_idxs['roadCameraState'], - frs['roadCameraState'].frame_count, frame_idxs['driverCameraState'], frs['driverCameraState'].frame_count)) + if spinner: + spinner.update("replaying models: road %d/%d, driver %d/%d" % (frame_idxs['roadCameraState'], + frs['roadCameraState'].frame_count, frame_idxs['driverCameraState'], frs['driverCameraState'].frame_count)) + - if any(frame_idxs[c] >= frs[c].frame_count for c in frame_idxs.keys()): + if any(frame_idxs[c] >= frs[c].frame_count for c in frame_idxs.keys()) or frame_idxs['roadCameraState'] == MAX_FRAMES: break + else: + print(f'Received {frame_idxs["roadCameraState"]} frames') finally: - spinner.close() + if spinner: + spinner.close() managed_processes['modeld'].stop() managed_processes['dmonitoringmodeld'].stop() @@ -144,9 +151,8 @@ if __name__ == "__main__": frs = { 'roadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="fcamera")), 'driverCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="dcamera")), + 'wideRoadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="ecamera")) } - if TICI: - frs['wideRoadCameraState'] = FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="ecamera")) # run replay log_msgs = model_replay(lr, frs) @@ -156,9 +162,9 @@ if __name__ == "__main__": if not update: with open(ref_commit_fn) as f: ref_commit = f.read().strip() - log_fn = get_log_fn(ref_commit, TEST_ROUTE, tici=TICI) + log_fn = get_log_fn(ref_commit, TEST_ROUTE) try: - cmp_log = LogReader(BASE_URL + log_fn) + cmp_log = list(LogReader(BASE_URL + log_fn))[:2*MAX_FRAMES] ignore = [ 'logMonoTime', @@ -167,7 +173,8 @@ if __name__ == "__main__": 'driverStateV2.modelExecutionTime', 'driverStateV2.dspExecutionTime' ] - tolerance = None if not PC else 1e-3 + # TODO this tolerence is absurdly large + tolerance = 5e-1 if PC else None results: Any = {TEST_ROUTE: {}} results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) diff1, diff2, failed = format_diff(results, ref_commit) @@ -182,13 +189,13 @@ if __name__ == "__main__": failed = True # upload new refs - if update or failed: + if (update or failed) and not PC: from selfdrive.test.openpilotci import upload_file print("Uploading new refs") new_commit = get_commit() - log_fn = get_log_fn(new_commit, TEST_ROUTE, tici=TICI) + log_fn = get_log_fn(new_commit, TEST_ROUTE) save_log(log_fn, log_msgs) try: upload_file(log_fn, os.path.basename(log_fn)) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 502fa15f2a..3a9b1d9479 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -49e231ccf06ef35994a3ec907af959c28e3c0870 \ No newline at end of file +0e18bb3317437f2cad6d0a5782a9222eda655d58 diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index bcc91b3ab6..653efaf32c 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -3,8 +3,8 @@ import bz2 import os import time import multiprocessing -from tqdm import tqdm import argparse +from tqdm import tqdm # run DM procs os.environ["USE_WEBCAM"] = "1" @@ -24,7 +24,6 @@ from tools.lib.route import Route from tools.lib.framereader import FrameReader from tools.lib.logreader import LogReader - def replay_panda_states(s, msgs): pm = messaging.PubMaster([s, 'peripheralState']) rk = Ratekeeper(service_list[s].frequency, print_delay_threshold=None) @@ -118,7 +117,7 @@ def replay_service(s, msgs): rk.keep_time() -def replay_cameras(lr, frs): +def replay_cameras(lr, frs, disable_tqdm=False): eon_cameras = [ ("roadCameraState", DT_MDL, eon_f_frame_size, VisionStreamType.VISION_STREAM_ROAD, True), ("driverCameraState", DT_DMON, eon_d_frame_size, VisionStreamType.VISION_STREAM_DRIVER, False), @@ -163,7 +162,7 @@ def replay_cameras(lr, frs): if fr is not None: print(f"Decompressing frames {s}") frames = [] - for i in tqdm(range(fr.frame_count)): + for i in tqdm(range(fr.frame_count), disable=disable_tqdm): img = fr.get(i, pix_fmt='nv12')[0] frames.append(img.flatten().tobytes()) @@ -177,7 +176,7 @@ def replay_cameras(lr, frs): return vs, p -def regen_segment(lr, frs=None, outdir=FAKEDATA): +def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): lr = list(lr) if frs is None: frs = dict() @@ -207,7 +206,7 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA): elif msg.which() == 'liveCalibration': params.put("CalibrationParams", msg.as_builder().to_bytes()) - vs, cam_procs = replay_cameras(lr, frs) + vs, cam_procs = replay_cameras(lr, frs, disable_tqdm=disable_tqdm) fake_daemons = { 'sensord': [ @@ -219,7 +218,7 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA): multiprocessing.Process(target=replay_panda_states, args=('pandaStates', lr)), ], 'managerState': [ - multiprocessing.Process(target=replay_manager_state, args=('managerState', lr)), + multiprocessing.Process(target=replay_manager_state, args=('managerState', lr)), ], 'thermald': [ multiprocessing.Process(target=replay_device_state, args=('deviceState', lr)), @@ -236,13 +235,13 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA): time.sleep(5) # start procs up - ignore = list(fake_daemons.keys()) + ['ui', 'manage_athenad', 'uploader'] + ignore = list(fake_daemons.keys()) + ['ui', 'manage_athenad', 'uploader', 'soundd'] ensure_running(managed_processes.values(), started=True, params=Params(), CP=car.CarParams(), not_run=ignore) for procs in fake_daemons.values(): for p in procs: p.start() - for _ in tqdm(range(60)): + for _ in tqdm(range(60), disable=disable_tqdm): # ensure all procs are running for d, procs in fake_daemons.items(): for p in procs: @@ -268,7 +267,7 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA): return seg_path -def regen_and_save(route, sidx, upload=False, use_route_meta=False): +def regen_and_save(route, sidx, upload=False, use_route_meta=False, outdir=FAKEDATA, disable_tqdm=False): if use_route_meta: r = Route(args.route) lr = LogReader(r.log_paths()[args.seg]) @@ -276,7 +275,7 @@ def regen_and_save(route, sidx, upload=False, use_route_meta=False): else: lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog.bz2") fr = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc") - rpath = regen_segment(lr, {'roadCameraState': fr}) + rpath = regen_segment(lr, {'roadCameraState': fr}, outdir=outdir, disable_tqdm=disable_tqdm) # compress raw rlog before uploading with open(os.path.join(rpath, "rlog"), "rb") as f: @@ -294,7 +293,7 @@ def regen_and_save(route, sidx, upload=False, use_route_meta=False): print("\n\n", "*"*30, "\n\n") print("New route:", relr, "\n") if upload: - upload_route(relr) + upload_route(relr, exclude_patterns=['*.hevc', ]) return relr diff --git a/selfdrive/test/process_replay/regen_all.py b/selfdrive/test/process_replay/regen_all.py index 4f057bbf50..765e5c3b68 100755 --- a/selfdrive/test/process_replay/regen_all.py +++ b/selfdrive/test/process_replay/regen_all.py @@ -1,22 +1,36 @@ #!/usr/bin/env python3 +import argparse +import concurrent.futures +import os +import random +from tqdm import tqdm + +from selfdrive.test.process_replay.helpers import OpenpilotPrefix from selfdrive.test.process_replay.regen import regen_and_save -from selfdrive.test.process_replay.test_processes import original_segments as segments +from selfdrive.test.process_replay.test_processes import FAKEDATA, original_segments as segments -if __name__ == "__main__": - new_segments = [] - for segment in segments: +def regen_job(segment): + with OpenpilotPrefix(): route = segment[1].rsplit('--', 1)[0] sidx = int(segment[1].rsplit('--', 1)[1]) - print("Regen", route, sidx) - relr = regen_and_save(route, sidx, upload=True, use_route_meta=False) + fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for i in range(11)) + try: + relr = regen_and_save(route, sidx, upload=True, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=True) + relr = '|'.join(relr.split('/')[-2:]) + return f' ("{segment[0]}", "{relr}"), ' + except Exception as e: + return f" {segment} failed: {str(e)}" + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Generate new segments from old ones") + parser.add_argument("-j", "--jobs", type=int, default=1) + args = parser.parse_args() - print("\n\n", "*"*30, "\n\n") - print("New route:", relr, "\n") - relr = relr.replace('/', '|') - new_segments.append(f' ("{segment[0]}", "{relr}"), ') - print() - print() - print() - print('COPY THIS INTO test_processes.py') - for seg in new_segments: - print(seg) + with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: + p = list(pool.map(regen_job, segments)) + msg = "Copy these new segments into test_processes.py:" + for seg in tqdm(p, desc="Generating segments"): + msg += "\n" + str(seg) + print() + print() + print(msg) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 1d5969b1ec..c1b5b85391 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -59,9 +59,9 @@ REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") def run_test_process(data): segment, cfg, args, cur_log_fn, ref_log_path, lr_dat = data - lr = LogReader.from_bytes(lr_dat) 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) # save logs so we can upload when updating refs save_log(cur_log_fn, log_msgs) @@ -160,7 +160,7 @@ if __name__ == "__main__": tested_cars = set(args.whitelist_cars) - set(args.blacklist_cars) tested_cars = {c.upper() for c in tested_cars} - full_test = all(len(x) == 0 for x in (args.whitelist_procs, args.whitelist_cars, args.blacklist_procs, args.blacklist_cars, args.ignore_fields, args.ignore_msgs)) + full_test = (tested_procs == all_procs) and (tested_cars == all_cars) and all(len(x) == 0 for x in (args.ignore_fields, args.ignore_msgs)) upload = args.update_refs or args.upload_only os.makedirs(os.path.dirname(FAKEDATA), exist_ok=True) @@ -181,8 +181,7 @@ if __name__ == "__main__": # check to make sure all car brands are tested if full_test: - tested_cars = {c.lower() for c, _ in segments} - untested = (set(interface_names) - set(excluded_interfaces)) - tested_cars + untested = (set(interface_names) - set(excluded_interfaces)) - {c.lower() for c in tested_cars} assert len(untested) == 0, f"Cars missing routes: {str(untested)}" with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index b388e599f7..99a63b8dfd 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -18,8 +18,12 @@ DEST_KEY = azureutil.get_user_token(_DATA_ACCOUNT_CI, "openpilotci") SOURCE_KEYS = [azureutil.get_user_token(account, bucket) for account, bucket in SOURCES] SERVICE = BlockBlobService(_DATA_ACCOUNT_CI, sas_token=DEST_KEY) -def upload_route(path): +def upload_route(path, exclude_patterns=None): + if exclude_patterns is None: + exclude_patterns = ['*/dcamera.hevc'] + r, n = path.rsplit("--", 1) + r = '/'.join(r.split('/')[-2:]) # strip out anything extra in the path destpath = f"{r}/{n}" cmd = [ "azcopy", @@ -28,9 +32,7 @@ def upload_route(path): f"https://{_DATA_ACCOUNT_CI}.blob.core.windows.net/openpilotci/{destpath}?{DEST_KEY}", "--recursive=false", "--overwrite=false", - "--exclude-pattern=*/dcamera.hevc", - "--exclude-pattern=*.mkv", - ] + ] + [f"--exclude-pattern={p}" for p in exclude_patterns] subprocess.check_call(cmd) def sync_to_ci_public(route): diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 4aff797714..ac6f1f1ba0 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -57,12 +57,6 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { "Upload data from the driver facing camera and help improve the driver monitoring algorithm.", "../assets/offroad/icon_monitoring.png", }, - { - "EndToEndToggle", - "\U0001f96c Disable use of lanelines (Alpha) \U0001f96c", - "In this mode openpilot will ignore lanelines and just drive how it thinks a human would.", - "../assets/offroad/icon_road.png", - }, { "DisengageOnAccelerator", "Disengage On Accelerator Pedal", @@ -95,9 +89,6 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { auto toggle = new ParamControl(param, title, desc, icon, this); bool locked = params.getBool((param + "Lock").toStdString()); toggle->setEnabled(!locked); - if (!locked) { - connect(uiState(), &UIState::offroadTransition, toggle, &ParamControl::setEnabled); - } addItem(toggle); } } diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 31d94c2c65..e549f62a23 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -166,7 +166,6 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { NvgWindow::NvgWindow(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraViewWidget("camerad", type, true, parent) { engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); - dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size}); } void NvgWindow::updateState(const UIState &s) { @@ -186,13 +185,11 @@ void NvgWindow::updateState(const UIState &s) { setProperty("speed", QString::number(std::nearbyint(cur_speed))); setProperty("maxSpeed", maxspeed_str); setProperty("speedUnit", s.scene.is_metric ? "km/h" : "mph"); - setProperty("hideDM", cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE); setProperty("status", s.status); - // update engageability and DM icons at 2Hz + // update engageability at 2Hz if (sm.frame % (UI_FREQ / 2) == 0) { setProperty("engageable", cs.getEngageable() || cs.getEnabled()); - setProperty("dmActive", sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode()); } } @@ -234,11 +231,6 @@ void NvgWindow::drawHud(QPainter &p) { engage_img, bg_colors[status], 1.0); } - // dm icon - if (!hideDM) { - drawIcon(p, radius / 2 + (bdr_s * 2), rect().bottom() - footer_h / 2, - dm_img, QColor(0, 0, 0, 70), dmActive ? 1.0 : 0.2); - } p.restore(); } @@ -311,24 +303,19 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { // paint path QLinearGradient bg(0, height(), 0, height() / 4); - if (scene.end_to_end) { - const auto &orientation = (*s->sm)["modelV2"].getModelV2().getOrientation(); - float orientation_future = 0; - if (orientation.getZ().size() > 16) { - orientation_future = std::abs(orientation.getZ()[16]); // 2.5 seconds - } - // straight: 112, in turns: 70 - float curve_hue = fmax(70, 112 - (orientation_future * 420)); - // FIXME: painter.drawPolygon can be slow if hue is not rounded - curve_hue = int(curve_hue * 100 + 0.5) / 100; - - bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); - bg.setColorAt(0.75 / 1.5, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.35)); - bg.setColorAt(1.0, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.0)); - } else { - bg.setColorAt(0, whiteColor()); - bg.setColorAt(1, whiteColor(0)); + const auto &orientation = (*s->sm)["modelV2"].getModelV2().getOrientation(); + float orientation_future = 0; + if (orientation.getZ().size() > 16) { + orientation_future = std::abs(orientation.getZ()[16]); // 2.5 seconds } + // straight: 112, in turns: 70 + float curve_hue = fmax(70, 112 - (orientation_future * 420)); + // FIXME: painter.drawPolygon can be slow if hue is not rounded + curve_hue = int(curve_hue * 100 + 0.5) / 100; + + bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); + bg.setColorAt(0.75 / 1.5, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.35)); + bg.setColorAt(1.0, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.0)); painter.setBrush(bg); painter.drawPolygon(scene.track_vertices.v, scene.track_vertices.cnt); diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 6ca2b3c738..e1f665149e 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -32,8 +32,6 @@ class NvgWindow : public CameraViewWidget { Q_PROPERTY(QString maxSpeed MEMBER maxSpeed); Q_PROPERTY(bool is_cruise_set MEMBER is_cruise_set); Q_PROPERTY(bool engageable MEMBER engageable); - Q_PROPERTY(bool dmActive MEMBER dmActive); - Q_PROPERTY(bool hideDM MEMBER hideDM); Q_PROPERTY(int status MEMBER status); public: @@ -45,7 +43,6 @@ private: void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); QPixmap engage_img; - QPixmap dm_img; const int radius = 192; const int img_size = (radius / 2) * 1.5; QString speed; @@ -53,8 +50,6 @@ private: QString maxSpeed; bool is_cruise_set = false; bool engageable = false; - bool dmActive = false; - bool hideDM = false; int status = STATUS_DISENGAGED; protected: diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 27d472535b..8a208bf3cf 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -198,7 +198,7 @@ PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QFrame(parent) { main_layout->addWidget(features, 0, Qt::AlignBottom); main_layout->addSpacing(30); - QVector bullets = {"Remote access", "14 days of storage", "Developer perks"}; + QVector bullets = {"Remote access", "1 year of storage", "Developer perks"}; for (auto &b: bullets) { const QString check = " "; QLabel *l = new QLabel(check + b); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 811438832b..f7c2c90437 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -114,7 +114,7 @@ static void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) { max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance); } max_idx = get_path_length_idx(model_position, max_distance); - update_line_data(s, model_position, scene.end_to_end ? 0.9 : 0.5, 1.22, &scene.track_vertices, max_idx, false); + update_line_data(s, model_position, 0.9, 1.22, &scene.track_vertices, max_idx, false); } static void update_sockets(UIState *s) { @@ -221,7 +221,6 @@ void UIState::updateStatus() { if (scene.started) { status = STATUS_DISENGAGED; scene.started_frame = sm->frame; - scene.end_to_end = Params().getBool("EndToEndToggle"); wide_camera = Params().getBool("WideCameraOnly"); } started_prev = scene.started; @@ -232,7 +231,7 @@ void UIState::updateStatus() { UIState::UIState(QObject *parent) : QObject(parent) { sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", - "pandaStates", "carParams", "driverMonitoringState", "sensorEvents", "carState", "liveLocationKalman", + "pandaStates", "carParams", "sensorEvents", "carState", "liveLocationKalman", "wideRoadCameraState", "managerState", "navInstruction", "navRoute", }); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 51a1f6e21f..192a353ad1 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -107,7 +107,7 @@ typedef struct UIScene { QPointF lead_vertices[2]; float light_sensor, accel_sensor, gyro_sensor; - bool started, ignition, is_metric, longitudinal_control, end_to_end; + bool started, ignition, is_metric, longitudinal_control; uint64_t started_frame; } UIScene; diff --git a/selfdrive/clocksd/.gitignore b/system/clocksd/.gitignore similarity index 100% rename from selfdrive/clocksd/.gitignore rename to system/clocksd/.gitignore diff --git a/selfdrive/clocksd/SConscript b/system/clocksd/SConscript similarity index 100% rename from selfdrive/clocksd/SConscript rename to system/clocksd/SConscript diff --git a/selfdrive/clocksd/clocksd.cc b/system/clocksd/clocksd.cc similarity index 100% rename from selfdrive/clocksd/clocksd.cc rename to system/clocksd/clocksd.cc diff --git a/selfdrive/logcatd/.gitignore b/system/logcatd/.gitignore similarity index 100% rename from selfdrive/logcatd/.gitignore rename to system/logcatd/.gitignore diff --git a/selfdrive/logcatd/SConscript b/system/logcatd/SConscript similarity index 100% rename from selfdrive/logcatd/SConscript rename to system/logcatd/SConscript diff --git a/selfdrive/logcatd/logcatd_systemd.cc b/system/logcatd/logcatd_systemd.cc similarity index 100% rename from selfdrive/logcatd/logcatd_systemd.cc rename to system/logcatd/logcatd_systemd.cc diff --git a/selfdrive/proclogd/SConscript b/system/proclogd/SConscript similarity index 100% rename from selfdrive/proclogd/SConscript rename to system/proclogd/SConscript diff --git a/selfdrive/proclogd/main.cc b/system/proclogd/main.cc similarity index 89% rename from selfdrive/proclogd/main.cc rename to system/proclogd/main.cc index 288238dc9a..c4faa916d9 100644 --- a/selfdrive/proclogd/main.cc +++ b/system/proclogd/main.cc @@ -2,7 +2,7 @@ #include #include "common/util.h" -#include "selfdrive/proclogd/proclog.h" +#include "system/proclogd/proclog.h" ExitHandler do_exit; diff --git a/selfdrive/proclogd/proclog.cc b/system/proclogd/proclog.cc similarity index 99% rename from selfdrive/proclogd/proclog.cc rename to system/proclogd/proclog.cc index 215d9e9df0..9064547d29 100644 --- a/selfdrive/proclogd/proclog.cc +++ b/system/proclogd/proclog.cc @@ -1,4 +1,4 @@ -#include "selfdrive/proclogd/proclog.h" +#include "system/proclogd/proclog.h" #include diff --git a/selfdrive/proclogd/proclog.h b/system/proclogd/proclog.h similarity index 100% rename from selfdrive/proclogd/proclog.h rename to system/proclogd/proclog.h diff --git a/selfdrive/proclogd/tests/.gitignore b/system/proclogd/tests/.gitignore similarity index 100% rename from selfdrive/proclogd/tests/.gitignore rename to system/proclogd/tests/.gitignore diff --git a/selfdrive/proclogd/tests/test_proclog.cc b/system/proclogd/tests/test_proclog.cc similarity index 99% rename from selfdrive/proclogd/tests/test_proclog.cc rename to system/proclogd/tests/test_proclog.cc index 3e346988c6..230e855acb 100644 --- a/selfdrive/proclogd/tests/test_proclog.cc +++ b/system/proclogd/tests/test_proclog.cc @@ -1,7 +1,7 @@ #define CATCH_CONFIG_MAIN #include "catch2/catch.hpp" #include "common/util.h" -#include "selfdrive/proclogd/proclog.h" +#include "system/proclogd/proclog.h" const std::string allowed_states = "RSDTZtWXxKWPI"; diff --git a/tools/plotjuggler/layouts/torque-controller.xml b/tools/plotjuggler/layouts/torque-controller.xml new file mode 100644 index 0000000000..661bfe094d --- /dev/null +++ b/tools/plotjuggler/layouts/torque-controller.xml @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + return (value * v1 ^ 2) - (v2 * 9.81) + /controlsState/curvature + + /carState/vEgo + /liveParameters/roll + + + + + return (value * v1 ^ 2) - (v2 * 9.81) + /controlsState/desiredCurvature + + /carState/vEgo + /liveParameters/roll + + + + + + diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim index 27cf25550f..d869db90a6 100644 --- a/tools/sim/Dockerfile.sim +++ b/tools/sim/Dockerfile.sim @@ -1,41 +1,10 @@ -FROM ghcr.io/commaai/openpilot-base:latest +FROM ghcr.io/commaai/openpilot-base-cl:latest RUN apt-get update && apt-get install -y --no-install-recommends\ - apt-utils \ - unzip \ - tar \ - curl \ - xz-utils \ - alien \ - dbus \ - gcc-arm-none-eabi \ tmux \ vim \ - lsb-core \ - libx11-6 \ && rm -rf /var/lib/apt/lists/* -# Intel OpenCL driver -ARG INTEL_DRIVER=l_opencl_p_18.1.0.015.tgz -ARG INTEL_DRIVER_URL=http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532 -RUN mkdir -p /tmp/opencl-driver-intel -WORKDIR /tmp/opencl-driver-intel -RUN echo INTEL_DRIVER is $INTEL_DRIVER && \ - curl -O $INTEL_DRIVER_URL/$INTEL_DRIVER && \ - tar -xzf $INTEL_DRIVER && \ - for i in $(basename $INTEL_DRIVER .tgz)/rpm/*.rpm; do alien --to-deb $i; done && \ - dpkg -i *.deb && \ - rm -rf $INTEL_DRIVER $(basename $INTEL_DRIVER .tgz) *.deb && \ - mkdir -p /etc/OpenCL/vendors && \ - echo /opt/intel/opencl_compilers_and_libraries_18.1.0.015/linux/compiler/lib/intel64_lin/libintelocl.so > /etc/OpenCL/vendors/intel.icd && \ - rm -rf /tmp/opencl-driver-intel - -ENV NVIDIA_VISIBLE_DEVICES all -ENV NVIDIA_DRIVER_CAPABILITIES graphics,utility,compute -ENV QTWEBENGINE_DISABLE_SANDBOX 1 - -RUN dbus-uuidgen > /etc/machine-id - # get same tmux config used on NEOS for debugging RUN cd $HOME && \ curl -O https://raw.githubusercontent.com/commaai/eon-neos-builder/master/devices/eon/home/.tmux.conf @@ -54,6 +23,7 @@ COPY ./opendbc $HOME/openpilot/opendbc COPY ./cereal $HOME/openpilot/cereal COPY ./panda $HOME/openpilot/panda COPY ./selfdrive $HOME/openpilot/selfdrive +COPY ./system $HOME/openpilot/system COPY ./tools $HOME/openpilot/tools WORKDIR $HOME/openpilot diff --git a/tools/sim/README.md b/tools/sim/README.md index c77bd718ac..cb1aea35ac 100644 --- a/tools/sim/README.md +++ b/tools/sim/README.md @@ -46,8 +46,8 @@ All inputs: | key | functionality | |:----:|:-----------------:| -| 1 | Cruise up 5 mph | -| 2 | Cruise down 5 mph | +| 1 | Cruise up 1 mph | +| 2 | Cruise down 1 mph | | 3 | Cruise cancel | | q | Exit all | | wasd | Control manually |